diff --git a/fuse_constraints/CMakeLists.txt b/fuse_constraints/CMakeLists.txt index c5886f3d4..464d8d9c5 100644 --- a/fuse_constraints/CMakeLists.txt +++ b/fuse_constraints/CMakeLists.txt @@ -45,6 +45,9 @@ add_library(${PROJECT_NAME} src/absolute_pose_2d_stamped_constraint.cpp src/absolute_pose_3d_stamped_constraint.cpp src/fixed_3d_landmark_constraint.cpp + src/fixed_3d_landmark_simple_covariance_constraint.cpp + src/reprojection_error_constraint.cpp + src/reprojection_error_snavelly_constraint.cpp src/marginal_constraint.cpp src/marginal_cost_function.cpp src/marginalize_variables.cpp @@ -266,6 +269,79 @@ if(CATKIN_ENABLE_TESTING) CXX_STANDARD_REQUIRED YES ) + # Reprojection Error Constraint Tests + catkin_add_gtest(test_reprojection_error_constraint + test/test_reprojection_error_constraint.cpp + ) + add_dependencies(test_reprojection_error_constraint + ${catkin_EXPORTED_TARGETS} + ) + target_include_directories(test_reprojection_error_constraint + PRIVATE + include + ${catkin_INCLUDE_DIRS} + ${CERES_INCLUDE_DIRS} + ) + target_link_libraries(test_reprojection_error_constraint + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ${CERES_LIBRARIES} + ) + set_target_properties(test_reprojection_error_constraint + PROPERTIES + CXX_STANDARD 17 + CXX_STANDARD_REQUIRED YES + ) + + # Reprojection Error Snavelly Constraint Tests + catkin_add_gtest(test_reprojection_error_snavelly_constraint + test/test_reprojection_error_snavelly_constraint.cpp + ) + add_dependencies(test_reprojection_error_snavelly_constraint + ${catkin_EXPORTED_TARGETS} + ) + target_include_directories(test_reprojection_error_snavelly_constraint + PRIVATE + include + ${catkin_INCLUDE_DIRS} + ${CERES_INCLUDE_DIRS} + ) + target_link_libraries(test_reprojection_error_snavelly_constraint + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ${CERES_LIBRARIES} + ) + set_target_properties(test_reprojection_error_snavelly_constraint + PROPERTIES + CXX_STANDARD 17 + CXX_STANDARD_REQUIRED YES + ) + + # BAL Problem Tests + catkin_add_gtest(test_bal_problem + test/test_bal_problem.cpp + WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/test + ) + add_dependencies(test_bal_problem + ${catkin_EXPORTED_TARGETS} + ) + target_include_directories(test_bal_problem + PRIVATE + include + ${catkin_INCLUDE_DIRS} + ${CERES_INCLUDE_DIRS} + ) + target_link_libraries(test_bal_problem + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ${CERES_LIBRARIES} + ) + set_target_properties(test_bal_problem + PROPERTIES + CXX_STANDARD 17 + CXX_STANDARD_REQUIRED YES + ) + # Absolute Pose 3D Stamped Constraint Tests catkin_add_gtest(test_absolute_pose_3d_stamped_constraint test/test_absolute_pose_3d_stamped_constraint.cpp diff --git a/fuse_constraints/include/fuse_constraints/fixed_3d_landmark_cost_functor.h b/fuse_constraints/include/fuse_constraints/fixed_3d_landmark_cost_functor.h index 7f7433aad..7851c8be4 100644 --- a/fuse_constraints/include/fuse_constraints/fixed_3d_landmark_cost_functor.h +++ b/fuse_constraints/include/fuse_constraints/fixed_3d_landmark_cost_functor.h @@ -176,13 +176,35 @@ bool Fixed3DLandmarkCostFunctor::operator()(const T* const position, const T* co auto d = (obs_.cast() - xp.block(0, 0, xp.rows(), 2)); - for (uint i = 0; i < 4; i++) + T fx = calibration[0]; + T fy = calibration[1]; + for (uint i = 0; i < pts3d_.cols(); i++) { - residual[i * 2] = d.row(i)[0]; - residual[i * 2 + 1] = d.row(i)[1]; + // Get the covariance weigthing to point losses from a pose uncertainty + // From https://arxiv.org/pdf/2103.15980.pdf , equation A.7: + // dh( e A p ) = dh(p') * d(e A p) + // d(e) d(p') d(e) + // where e is a small increment around the SE(3) manifold of A, A is a pose, p is a point, + // h is the projection function, and p' = Ap = g, the jacobian is thus 2x6: + // J = + // [ (fx/gz) (0) (-fx * gx / gz^2) (-fx * gx gy / gz^2) fx(1+gx^2/gz^2) -fx gy/gz] + // [ 0 (fy/gz)) (-fy * gy / gz^2) -fy(1+gy^2/gz^2) (-fy * gx gy / gz^2) -fy gx/gz] + T gx = pts3d_.cast().col(i)[0]; + T gy = pts3d_.cast().col(i)[1]; + T gz = pts3d_.cast().col(i)[2]; + T gz2 = gz*gz; + T gxyz = (gx*gy)/gz2; + Eigen::Matrix J; + J << fx/gz, T(0), -fx * (gx / gz2), -fx*gxyz, fx*(T(1)+(gx*gx)/gz2), -fx * gy/gz, + T(0), fy/gz, -fy * (gy / gz2), -fy*(T(1)+(gy*gy)/gz2), fy*gxyz, fy * gx/gz; + Eigen::Matrix A = J*A_*J.transpose(); + + // Weight Residuals + auto r = A * d.row(i).transpose(); + residual[i * 2] = r[0]; + residual[i * 2 + 1] = r[1]; } - // TODO(omendez): how do we apply covariance weigthing to point losses from a pose uncertainty? return true; } diff --git a/fuse_constraints/include/fuse_constraints/reprojection_error_constraint.h b/fuse_constraints/include/fuse_constraints/reprojection_error_constraint.h new file mode 100644 index 000000000..b56af00a0 --- /dev/null +++ b/fuse_constraints/include/fuse_constraints/reprojection_error_constraint.h @@ -0,0 +1,179 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Mon Dec 11 2023 + * + * Copyright (c) 2023, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef FUSE_CONSTRAINTS_REPROJECTION_ERROR_CONSTRAINT_H +#define FUSE_CONSTRAINTS_REPROJECTION_ERROR_CONSTRAINT_H + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +namespace fuse_constraints +{ + +/** + * @brief A constraint that represents an observation of a 3D point using a Pinhole camera model + * which contains 4 paramters (fx, fy, cx, cy) + * + * A landmark is represented as a 3D point . This class takes the location of the 3D landmark and + * applies a reprojection-error based constraint on the position, orientation and calibration of + * the camera that observed the landmark. + * + */ +class ReprojectionErrorConstraint : public fuse_core::Constraint +{ +public: + FUSE_CONSTRAINT_DEFINITIONS_WITH_EIGEN(ReprojectionErrorConstraint); + + /** + * @brief Default constructor + */ + ReprojectionErrorConstraint() = default; + + /** + * @brief Create a constraint + * + * @param[in] source The name of the sensor or motion model that generated this constraint + * @param[in] position The variable representing the position components of the camera pose + * @param[in] orientation The variable representing the orientation components of the camera pose + * @param[in] calibraton The calibration parameters of the camera (4x1 vector: fx, fy, cx, cy). + * NOTE: Best practice is to fix this variable unless we have several observations + * with the same camera + * @param[in] mean The measured observation of the point as a vector (2x1 vector: u,v) + * @param[in] covariance The prior observation covariance (2x2 matrix: u, v) + */ + ReprojectionErrorConstraint(const std::string& source, + const fuse_variables::Position3DStamped& position, + const fuse_variables::Orientation3DStamped& orientation, + const fuse_variables::PinholeCamera& calibraton, + const fuse_core::Vector2d& mean, + const fuse_core::Matrix2d& covariance); + + /** + * @brief Destructor + */ + virtual ~ReprojectionErrorConstraint() = default; + + /** + * @brief Read-only access to the square root information matrix. + * + * Order is (u, v) + */ + const fuse_core::Matrix2d& sqrtInformation() const + { + return sqrt_information_; + } + + /** + * @brief Read-only access to the measured/prior vector of mean values. + * + * Order is (u, v) + */ + const fuse_core::Vector2d& mean() const + { + return mean_; + } + + /** + * @brief Compute the measurement covariance matrix. + * + * Order is (u, v) + */ + fuse_core::Matrix2d covariance() const + { + return (sqrt_information_.transpose() * sqrt_information_).inverse(); + } + + /** + * @brief Print a human-readable description of the constraint to the provided stream. + * + * @param[out] stream The stream to write to. Defaults to stdout. + */ + void print(std::ostream& stream = std::cout) const override; + + /** + * @brief Construct an instance of this constraint's cost function + * + * The function caller will own the new cost function instance. It is the responsibility of the caller to delete + * the cost function object when it is no longer needed. If the pointer is provided to a Ceres::Problem object, the + * Ceres::Problem object will takes ownership of the pointer and delete it during destruction. + * + * @return A base pointer to an instance of a derived CostFunction. + */ + ceres::CostFunction* costFunction() const override; + +protected: + fuse_core::Vector2d mean_; //!< The 2D observations (in pixel space) + fuse_core::Matrix2d sqrt_information_; //!< The square root information matrix + +private: + // Allow Boost Serialization access to private methods + friend class boost::serialization::access; + + /** + * @brief The Boost Serialize method that serializes all of the data members in to/out of the archive + * + * @param[in/out] archive - The archive object that holds the serialized class members + * @param[in] version - The version of the archive being read/written. Generally unused. + */ + template + void serialize(Archive& archive, const unsigned int /* version */) + { + archive& boost::serialization::base_object(*this); + archive& mean_; + archive& sqrt_information_; + } +}; + +} // namespace fuse_constraints + +BOOST_CLASS_EXPORT_KEY(fuse_constraints::ReprojectionErrorConstraint); + +#endif // FUSE_CONSTRAINTS_REPROJECTION_ERROR_CONSTRAINT_H diff --git a/fuse_constraints/include/fuse_constraints/reprojection_error_cost_functor.h b/fuse_constraints/include/fuse_constraints/reprojection_error_cost_functor.h new file mode 100644 index 000000000..f0e907c88 --- /dev/null +++ b/fuse_constraints/include/fuse_constraints/reprojection_error_cost_functor.h @@ -0,0 +1,140 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Mon Dec 12 2023 + * + * Copyright (c) 2023, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef FUSE_CONSTRAINTS_REPROJECTION_ERROR_COST_FUNCTOR_H +#define FUSE_CONSTRAINTS_REPROJECTION_ERROR_COST_FUNCTOR_H + +#include +#include +#include +#include + +#include + +namespace fuse_constraints +{ + +/** + * @brief Create a prior cost function on the marker position, minimising reprojection error. + * + * The Ceres::NormalPrior cost function only supports a single variable. This is a convenience cost function that + * applies a prior constraint on the 3D position, orientation and calibration variables at once. + * + * The cost function is of the form: + * + * cost(x) = || A * (K * [R_q | p] * [R_{b(3:6)} | b(0:2))] * X - x) || + * + * where, the matrix A and the vector b are fixed, p is the camera position variable, and q is the camera orientation + * variable, K is the calibration matrix created from the calibration variable, X is the set of marker 3D points, + * R_b(0:3) is the Rotation matrix from the fixed landmark orentation (b(3:6)), b(0:2) is the fixed landmark position + * and x is the 2D ovservations. + * + * Note that the covariance submatrix for the quaternion is 3x3, representing errors in the orientation local + * parameterization tangent space. In case the user is interested in implementing a cost function of the form + * + * cost(X) = (X - mu)^T S^{-1} (X - mu) + * + * where, mu is a vector and S is a covariance matrix, then, A = S^{-1/2}, i.e the matrix A is the square root + * information matrix (the inverse of the covariance). + */ +class ReprojectionErrorCostFunctor +{ +public: + FUSE_MAKE_ALIGNED_OPERATOR_NEW(); + + /** + * @brief Construct a cost function instance + * + * @param[in] A The residual weighting matrix, most likely derived from the square root information + * matrix in order (u, v) + * @param[in] b The 2D pose measurement or prior in order (u, v + * + **/ + ReprojectionErrorCostFunctor(const fuse_core::Matrix2d& A, const fuse_core::Vector2d& b); + + /** + * @brief Evaluate the cost function. Used by the Ceres optimization engine. + */ + template + bool operator()(const T* const position, const T* const orientation, const T* const calibration, const T* const point, + T* residual) const; + +private: + fuse_core::Matrix2d A_; + fuse_core::Vector2d b_; +}; + +ReprojectionErrorCostFunctor::ReprojectionErrorCostFunctor(const fuse_core::Matrix2d& A, const fuse_core::Vector2d& b) + : A_(A), b_(b) +{ +} + +template +bool ReprojectionErrorCostFunctor::operator()(const T* const position, const T* const orientation, + const T* const calibration, const T* const point, T* residual) const +{ + + // Point to Camera CF ( X' = [R|t] X = RX + t ) + // Rotate Point (RX) + T p[3]; + ceres::QuaternionRotatePoint(orientation, point, p); + + // Ofset (+t) + p[0] += position[0]; + p[1] += position[1]; + p[2] += position[2]; + + // Project to camera ([u,v] = KX) + // u = (x'fx + z'cx)/z' + // v = (y'fy + z'cy)/z' + T uv[2]; + uv[0] = (p[0] * calibration[0] + p[2] * calibration[2]) / p[2]; + uv[1] = (p[1] * calibration[1] + p[2] * calibration[3]) / p[2]; + + // Get Residuals + residual[0] = uv[0] - b_[0]; + residual[1] = uv[1] - b_[1]; + + // Weight Residuals + Eigen::Map> residual_map(residual); + residual_map.applyOnTheLeft(A_.template cast()); + + return true; +} + +} // namespace fuse_constraints + +#endif // FUSE_CONSTRAINTS_REPROJECTION_ERROR_COST_FUNCTOR_H diff --git a/fuse_constraints/include/fuse_constraints/reprojection_error_snavelly_constraint.h b/fuse_constraints/include/fuse_constraints/reprojection_error_snavelly_constraint.h new file mode 100644 index 000000000..236877463 --- /dev/null +++ b/fuse_constraints/include/fuse_constraints/reprojection_error_snavelly_constraint.h @@ -0,0 +1,177 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Mon Dec 11 2023 + * + * Copyright (c) 2023, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef FUSE_CONSTRAINTS_REPROJECTION_ERROR_SNAVELLY_CONSTRAINT_H +#define FUSE_CONSTRAINTS_REPROJECTION_ERROR_SNAVELLY_CONSTRAINT_H + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +namespace fuse_constraints +{ + +/** + * @brief A constraint that represents an observation of a 3D point using a Snavelly camera model + * which contains 3 paramters (f, r1, r2) + * + * A landmark is represented as a 3D point . This class takes the location of the 3D landmark and + * applies a reprojection-error based constraint on the position, orientation and calibration of + * the camera that observed the landmark. + * + */ +class ReprojectionErrorSnavellyConstraint : public fuse_core::Constraint +{ +public: + FUSE_CONSTRAINT_DEFINITIONS_WITH_EIGEN(ReprojectionErrorSnavellyConstraint); + + /** + * @brief Default constructor + */ + ReprojectionErrorSnavellyConstraint() = default; + + /** + * @brief Create a constraint + * + * @param[in] source The name of the sensor or motion model that generated this constraint + * @param[in] position The variable representing the position components of the camera pose + * @param[in] orientation The variable representing the orientation components of the camera pose + * @param[in] calibraton The calibration parameters of the camera (3x1 vector: f, r1, r2). + * NOTE: Best practice is to fix this variable unless we have several observations + * with the same camera + * @param[in] mean The measured observation of the point as a vector (2x1 vector: u,v) + * @param[in] covariance The prior observation covariance (2x2 matrix: u, v) + */ + ReprojectionErrorSnavellyConstraint(const std::string& source, const fuse_variables::Position3DStamped& position, + const fuse_variables::Orientation3DStamped& orientation, + const fuse_variables::PinholeCameraSimple& calibraton, + const fuse_core::Vector2d& mean, const fuse_core::Matrix2d& covariance); + + /** + * @brief Destructor + */ + virtual ~ReprojectionErrorSnavellyConstraint() = default; + + /** + * @brief Read-only access to the square root information matrix. + * + * Order is (u, v) + */ + const fuse_core::Matrix2d& sqrtInformation() const + { + return sqrt_information_; + } + + /** + * @brief Read-only access to the measured/prior vector of mean values. + * + * Order is (u, v) + */ + const fuse_core::Vector2d& mean() const + { + return mean_; + } + + /** + * @brief Compute the measurement covariance matrix. + * + * Order is (u, v) + */ + fuse_core::Matrix2d covariance() const + { + return (sqrt_information_.transpose() * sqrt_information_).inverse(); + } + + /** + * @brief Print a human-readable description of the constraint to the provided stream. + * + * @param[out] stream The stream to write to. Defaults to stdout. + */ + void print(std::ostream& stream = std::cout) const override; + + /** + * @brief Construct an instance of this constraint's cost function + * + * The function caller will own the new cost function instance. It is the responsibility of the caller to delete + * the cost function object when it is no longer needed. If the pointer is provided to a Ceres::Problem object, the + * Ceres::Problem object will takes ownership of the pointer and delete it during destruction. + * + * @return A base pointer to an instance of a derived CostFunction. + */ + ceres::CostFunction* costFunction() const override; + +protected: + fuse_core::Vector2d mean_; //!< The 2D observations (in pixel space) + fuse_core::Matrix2d sqrt_information_; //!< The square root information matrix + +private: + // Allow Boost Serialization access to private methods + friend class boost::serialization::access; + + /** + * @brief The Boost Serialize method that serializes all of the data members in to/out of the archive + * + * @param[in/out] archive - The archive object that holds the serialized class members + * @param[in] version - The version of the archive being read/written. Generally unused. + */ + template + void serialize(Archive& archive, const unsigned int /* version */) + { + archive& boost::serialization::base_object(*this); + archive& mean_; + archive& sqrt_information_; + } +}; + +} // namespace fuse_constraints + +BOOST_CLASS_EXPORT_KEY(fuse_constraints::ReprojectionErrorSnavellyConstraint); + +#endif // FUSE_CONSTRAINTS_REPROJECTION_ERROR_SNAVELLY_CONSTRAINT_H diff --git a/fuse_constraints/include/fuse_constraints/reprojection_error_snavelly_cost_functor.h b/fuse_constraints/include/fuse_constraints/reprojection_error_snavelly_cost_functor.h new file mode 100644 index 000000000..4e6057493 --- /dev/null +++ b/fuse_constraints/include/fuse_constraints/reprojection_error_snavelly_cost_functor.h @@ -0,0 +1,147 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Mon Dec 12 2023 + * + * Copyright (c) 2023, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef FUSE_CONSTRAINTS_REPROJECTION_ERROR_SNAVELLY_COST_FUNCTOR_H +#define FUSE_CONSTRAINTS_REPROJECTION_ERROR_SNAVELLY_COST_FUNCTOR_H + +#include +#include +#include + +#include + +namespace fuse_constraints +{ + +/** + * @brief Create a prior cost function on the marker position, minimising reprojection error. + * + * The Ceres::NormalPrior cost function only supports a single variable. This is a convenience cost function that + * applies a prior constraint on the 3D position, orientation and calibration variables at once. + * + * The cost function is of the form: + * + * cost(x) = || A * (K * [R_q | p] * [R_{b(3:6)} | b(0:2))] * X - x) || + * + * where, the matrix A and the vector b are fixed, p is the camera position variable, and q is the camera orientation + * variable, K is the calibration matrix created from the calibration variable (f, r1, r2), X is the set of marker 3D points, + * R_b(0:3) is the Rotation matrix from the fixed landmark orentation (b(3:6)), b(0:2) is the fixed landmark position + * and x is the 2D ovservations. + * + * Note that the covariance matrix is defined as a 2x2 error in pixel space, most likely a diagonal matrix. + */ +class ReprojectionErrorSnavellyCostFunctor +{ +public: + FUSE_MAKE_ALIGNED_OPERATOR_NEW(); + + /** + * @brief Construct a cost function instance + * + * @param[in] A The residual weighting matrix, most likely derived from the square root information + * matrix in order (u, v) + * @param[in] b The 2D measurement or prior in order (u, v) + * + **/ + ReprojectionErrorSnavellyCostFunctor(const fuse_core::Matrix2d& A, const fuse_core::Vector2d& b); + + /** + * @brief Evaluate the cost function. Used by the Ceres optimization engine. + */ + template + bool operator()(const T* const position, const T* const orientation, const T* const calibration, + const T* const point, T* residuals) const; + +private: + fuse_core::Matrix2d A_; + fuse_core::Vector2d b_; +}; + +ReprojectionErrorSnavellyCostFunctor::ReprojectionErrorSnavellyCostFunctor(const fuse_core::Matrix2d& A, + const fuse_core::Vector2d& b) + : A_(A) + , b_(b) +{ +} + +template +bool ReprojectionErrorSnavellyCostFunctor::operator()(const T* const position, const T* const orientation, + const T* const calibration, + const T* const point, + T* residuals) const +{ + // Point to Camera CF ( X' = [R|t] X = RX + t ) + // Rotate Point (RX) + T p[3]; + ceres::QuaternionRotatePoint(orientation, point, p); + + // Ofset (+t) + p[0]+=position[0]; + p[1]+=position[1]; + p[2]+=position[2]; + + // Compute the center of distortion. The sign change comes from + // the camera model that Noah Snavely's Bundler assumes, whereby + // the camera coordinate system has a negative z axis. + T uv[2]; + uv[0] = -p[0]/p[2]; + uv[1] = -p[1]/p[2]; + + // Apply second and fourth order radial distortion. + const T& l1 = calibration[1]; + const T& l2 = calibration[2]; + const T r2 = uv[0] * uv[0] + uv[1] * uv[1]; + const T dist = 1.0 + r2 * (l1 + l2 * r2); + + // Compute final projected point position. + const T& f = calibration[0]; + const T predicted_x = f * dist * uv[0]; + const T predicted_y = f * dist * uv[1]; + + // The error is the difference between the predicted and observed position. + residuals[0] = predicted_x - b_[0]; + residuals[1] = predicted_y - b_[1]; + + // Weight Residuals + Eigen::Map> residual_map(residuals); + residual_map.applyOnTheLeft(A_.template cast()); + + return true; +} + +} // namespace fuse_constraints + +#endif // FUSE_CONSTRAINTS_REPROJECTION_ERROR_SNAVELLY_COST_FUNCTOR_H diff --git a/fuse_constraints/src/fixed_3d_landmark_simple_covariance_constraint.cpp b/fuse_constraints/src/fixed_3d_landmark_simple_covariance_constraint.cpp new file mode 100644 index 000000000..c04aa0fe7 --- /dev/null +++ b/fuse_constraints/src/fixed_3d_landmark_simple_covariance_constraint.cpp @@ -0,0 +1,116 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Mon Nov 12 2023 + * + * Copyright (c) 2023, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include + +#include +#include +#include + +#include + +namespace fuse_constraints +{ + +Fixed3DLandmarkSimpleCovarianceConstraint::Fixed3DLandmarkSimpleCovarianceConstraint( + const std::string& source, const fuse_variables::Position3DStamped& position, + const fuse_variables::Orientation3DStamped& orientation, const fuse_variables::PinholeCamera& calibration, + const fuse_core::MatrixXd& pts3d, const fuse_core::MatrixXd& observations, const fuse_core::Vector7d& mean, + const fuse_core::Matrix2d& covariance) + : fuse_core::Constraint(source, { position.uuid(), orientation.uuid(), calibration.uuid() }) + , pts3d_(pts3d) + , observations_(observations) + , mean_(mean) + , sqrt_information_(covariance.inverse().llt().matrixU()) +{ + assert(pts3d_.cols() == 3); + assert(observations_.cols() == 2); + assert(pts3d_.rows() == observations_.rows()); +} + +Fixed3DLandmarkSimpleCovarianceConstraint::Fixed3DLandmarkSimpleCovarianceConstraint( + const std::string& source, const fuse_variables::Position3DStamped& position, + const fuse_variables::Orientation3DStamped& orientation, const fuse_variables::PinholeCamera& calibration, + const double& marker_size, const fuse_core::MatrixXd& observations, const fuse_core::Vector7d& mean, + const fuse_core::Matrix2d& covariance) + : fuse_core::Constraint(source, { position.uuid(), orientation.uuid(), calibration.uuid() }) + , pts3d_(4, 3) + , observations_(observations) + , mean_(mean) + , sqrt_information_(covariance.inverse().llt().matrixU()) +{ + // Define 3D Homogeneous 3D Points at origin, assume z-up + pts3d_ << -1.0, -1.0, 0.0, // NOLINT + -1.0, 1.0, 0.0, // NOLINT + 1.0, -1.0, 0.0, // NOLINT + 1.0, 1.0, 0.0; // NOLINT + pts3d_ *= marker_size; // Scalar Multiplication + + assert(pts3d_.cols() == 3); + assert(observations_.cols() == 2); + assert(pts3d_.rows() == observations_.rows()); +} + +void Fixed3DLandmarkSimpleCovarianceConstraint::print(std::ostream& stream) const +{ + stream << type() << "\n" + << " source: " << source() << "\n" + << " uuid: " << uuid() << "\n" + << " position variable: " << variables().at(0) << "\n" + << " orientation variable: " << variables().at(1) << "\n" + << " mean: " << mean().transpose() << "\n" + << " sqrt_info: " << sqrtInformation() << "\n" + << " observations: " << observations() << "\n"; + + if (loss()) + { + stream << " loss: "; + loss()->print(stream); + } +} + +ceres::CostFunction* Fixed3DLandmarkSimpleCovarianceConstraint::costFunction() const +{ + return new ceres::AutoDiffCostFunction( + new Fixed3DLandmarkSimpleCovarianceCostFunctor(sqrt_information_, mean_, observations_, pts3d_)); +} + +} // namespace fuse_constraints + +BOOST_CLASS_EXPORT_IMPLEMENT(fuse_constraints::Fixed3DLandmarkSimpleCovarianceConstraint); +PLUGINLIB_EXPORT_CLASS(fuse_constraints::Fixed3DLandmarkSimpleCovarianceConstraint, fuse_core::Constraint); diff --git a/fuse_constraints/src/reprojection_error_constraint.cpp b/fuse_constraints/src/reprojection_error_constraint.cpp new file mode 100644 index 000000000..9ac0208b2 --- /dev/null +++ b/fuse_constraints/src/reprojection_error_constraint.cpp @@ -0,0 +1,88 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Mon Dec 12 2023 + * + * Copyright (c) 2023, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include + +#include + +#include +#include +#include + +#include + +namespace fuse_constraints +{ + +ReprojectionErrorConstraint::ReprojectionErrorConstraint( + const std::string& source, const fuse_variables::Position3DStamped& position, + const fuse_variables::Orientation3DStamped& orientation, const fuse_variables::PinholeCamera& calibration, + const fuse_core::Vector2d& mean, + const fuse_core::Matrix2d& covariance) + : fuse_core::Constraint(source, { position.uuid(), orientation.uuid(), calibration.uuid() }) + , mean_(mean) + , sqrt_information_(covariance.inverse().llt().matrixU()) +{ +} + +void ReprojectionErrorConstraint::print(std::ostream& stream) const +{ + stream << type() << "\n" + << " source: " << source() << "\n" + << " uuid: " << uuid() << "\n" + << " position variable: " << variables().at(0) << "\n" + << " orientation variable: " << variables().at(1) << "\n" + << " mean: " << mean().transpose() << "\n" + << " sqrt_info: " << sqrtInformation() << "\n"; + + if (loss()) + { + stream << " loss: "; + loss()->print(stream); + } +} + +ceres::CostFunction* ReprojectionErrorConstraint::costFunction() const +{ + return new ceres::AutoDiffCostFunction( + new ReprojectionErrorCostFunctor(sqrt_information_, mean_)); +} + +} // namespace fuse_constraints + +BOOST_CLASS_EXPORT_IMPLEMENT(fuse_constraints::ReprojectionErrorConstraint); +PLUGINLIB_EXPORT_CLASS(fuse_constraints::ReprojectionErrorConstraint, fuse_core::Constraint); diff --git a/fuse_constraints/src/reprojection_error_snavelly_constraint.cpp b/fuse_constraints/src/reprojection_error_snavelly_constraint.cpp new file mode 100644 index 000000000..6db9f2e21 --- /dev/null +++ b/fuse_constraints/src/reprojection_error_snavelly_constraint.cpp @@ -0,0 +1,89 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Mon Dec 12 2023 + * + * Copyright (c) 2023, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include + +#include + +#include +#include +#include + +#include + +namespace fuse_constraints +{ + +ReprojectionErrorSnavellyConstraint::ReprojectionErrorSnavellyConstraint( + const std::string& source, const fuse_variables::Position3DStamped& position, + const fuse_variables::Orientation3DStamped& orientation, + const fuse_variables::PinholeCameraSimple& calibration, + const fuse_core::Vector2d& mean, + const fuse_core::Matrix2d& covariance) + : fuse_core::Constraint(source, { position.uuid(), orientation.uuid(), calibration.uuid() }) + , mean_(mean) + , sqrt_information_(covariance.inverse().llt().matrixU()) +{ +} + +void ReprojectionErrorSnavellyConstraint::print(std::ostream& stream) const +{ + stream << type() << "\n" + << " source: " << source() << "\n" + << " uuid: " << uuid() << "\n" + << " position variable: " << variables().at(0) << "\n" + << " orientation variable: " << variables().at(1) << "\n" + << " mean: " << mean().transpose() << "\n" + << " sqrt_info: " << sqrtInformation() << "\n"; + + if (loss()) + { + stream << " loss: "; + loss()->print(stream); + } +} + +ceres::CostFunction* ReprojectionErrorSnavellyConstraint::costFunction() const +{ + return new ceres::AutoDiffCostFunction( + new ReprojectionErrorSnavellyCostFunctor(sqrt_information_, mean_)); +} + +} // namespace fuse_constraints + +BOOST_CLASS_EXPORT_IMPLEMENT(fuse_constraints::ReprojectionErrorSnavellyConstraint); +PLUGINLIB_EXPORT_CLASS(fuse_constraints::ReprojectionErrorSnavellyConstraint, fuse_core::Constraint); diff --git a/fuse_constraints/test/problem-21-11315-pre.txt b/fuse_constraints/test/problem-21-11315-pre.txt new file mode 100644 index 000000000..4fc68d1b9 --- /dev/null +++ b/fuse_constraints/test/problem-21-11315-pre.txt @@ -0,0 +1,70590 @@ +21 11315 36455 +0 0 1.597070e+03 4.733700e+02 +1 0 7.217000e+02 5.229800e+02 +2 0 5.779100e+02 4.318900e+02 +3 0 6.169000e+02 6.129000e+02 +7 0 8.902600e+02 5.648201e+02 +12 0 -2.527600e+02 -2.743400e+02 +16 0 9.836899e+02 5.389399e+02 +17 0 -1.284400e+03 1.003560e+03 +0 1 1.641870e+03 4.786300e+02 +1 1 7.861699e+02 5.273800e+02 +2 1 6.186100e+02 4.345701e+02 +3 1 6.792100e+02 6.162900e+02 +7 1 9.178999e+02 5.671500e+02 +12 1 -2.264399e+02 -2.726400e+02 +0 2 6.032400e+02 2.375701e+02 +1 2 -8.372900e+02 2.858401e+02 +0 3 1.549640e+03 2.853800e+02 +1 3 9.312700e+02 2.975400e+02 +2 3 7.276000e+02 1.751200e+02 +4 3 1.483550e+03 3.825300e+02 +5 3 1.170520e+03 8.879800e+02 +6 3 8.161500e+02 1.737700e+02 +7 3 8.932500e+02 3.960500e+02 +8 3 7.967200e+02 3.767800e+02 +16 3 9.576899e+02 4.048600e+02 +17 3 -1.000180e+03 5.937000e+02 +0 4 1.682800e+03 4.789399e+02 +1 4 8.453701e+02 5.229399e+02 +2 4 6.598400e+02 4.310000e+02 +3 4 7.373700e+02 6.103500e+02 +7 4 9.474800e+02 5.659600e+02 +12 4 -2.008000e+02 -2.750601e+02 +17 4 -1.154410e+03 9.952600e+02 +18 4 2.812000e+01 1.941100e+02 +20 4 2.778003e+01 -2.881006e+01 +0 5 1.662390e+03 4.820500e+02 +1 5 8.192600e+02 5.325300e+02 +2 5 6.422000e+02 4.397300e+02 +3 5 7.134900e+02 6.212500e+02 +6 5 8.194301e+02 3.269200e+02 +7 5 9.331001e+02 5.703201e+02 +12 5 -2.128500e+02 -2.709800e+02 +17 5 -1.181620e+03 1.007340e+03 +18 5 1.908997e+01 1.970601e+02 +0 6 5.385701e+02 4.054299e+02 +1 6 -9.477700e+02 6.604500e+02 +2 6 -2.968600e+02 3.553900e+02 +4 6 8.799199e+02 4.434000e+02 +5 6 4.124000e+02 8.607800e+02 +7 6 2.339000e+02 4.944199e+02 +8 6 -7.436600e+02 6.023000e+02 +10 6 -2.499200e+02 -2.470100e+02 +11 6 3.185699e+02 3.400700e+02 +18 6 -4.786700e+02 1.381500e+02 +0 7 1.662660e+03 4.690901e+02 +1 7 8.166499e+02 5.083800e+02 +2 7 6.412700e+02 4.224200e+02 +3 7 7.098500e+02 5.958500e+02 +18 7 1.881006e+01 1.897300e+02 +0 8 1.627900e+03 4.864299e+02 +1 8 7.600100e+02 5.437900e+02 +2 8 6.008101e+02 4.472800e+02 +3 8 6.534700e+02 6.337600e+02 +6 8 7.781100e+02 3.342800e+02 +7 8 9.092500e+02 5.732000e+02 +12 8 -2.338800e+02 -2.671300e+02 +17 8 -1.242180e+03 1.021540e+03 +0 9 4.515300e+02 4.381400e+02 +1 9 -1.130420e+03 7.559600e+02 +2 9 -3.760200e+02 3.953500e+02 +4 9 8.290100e+02 4.585801e+02 +7 9 1.801600e+02 5.169399e+02 +8 9 -8.904300e+02 6.598300e+02 +9 9 -3.969200e+02 4.367100e+02 +10 9 -2.955900e+02 -2.272000e+02 +11 9 2.599100e+02 3.658500e+02 +12 9 -9.223100e+02 -3.233000e+02 +18 9 -5.177400e+02 1.566599e+02 +20 9 -4.393500e+02 -6.360999e+01 +0 10 1.696480e+03 1.835200e+02 +1 10 1.206880e+03 1.171899e+02 +7 10 9.820500e+02 3.247400e+02 +8 10 9.981000e+02 2.198600e+02 +9 10 5.838101e+02 2.006500e+02 +10 10 4.024399e+02 -3.961500e+02 +12 10 -1.516400e+02 -5.225601e+02 +17 10 -7.707200e+02 4.233700e+02 +18 10 8.810999e+01 -3.489990e+00 +0 11 1.696480e+03 1.835200e+02 +1 11 1.206880e+03 1.171899e+02 +6 11 1.014670e+03 4.053003e+01 +8 11 9.981000e+02 2.198600e+02 +9 11 5.838101e+02 2.006500e+02 +10 11 4.024399e+02 -3.961500e+02 +12 11 -1.516400e+02 -5.225601e+02 +17 11 -7.706300e+02 4.232200e+02 +18 11 8.810999e+01 -3.489990e+00 +20 11 8.234998e+01 -1.982800e+02 +0 12 5.469700e+02 1.750500e+02 +1 12 -9.454200e+02 1.703301e+02 +2 12 -2.931600e+02 8.088000e+01 +3 12 -9.249200e+02 2.976899e+02 +4 12 8.822500e+02 3.130601e+02 +5 12 4.425900e+02 6.886899e+02 +6 12 -5.436100e+02 1.095600e+02 +9 12 -3.272700e+02 1.999399e+02 +10 12 -2.472900e+02 -3.961899e+02 +11 12 3.227900e+02 1.382900e+02 +12 12 -8.730500e+02 -5.100800e+02 +0 13 1.593740e+03 1.776899e+02 +1 13 1.026040e+03 1.078000e+02 +6 13 8.774900e+02 3.527002e+01 +8 13 8.571500e+02 2.119500e+02 +12 13 -2.091899e+02 -5.231801e+02 +17 13 -9.200000e+02 4.222600e+02 +0 14 1.491960e+03 2.510400e+02 +1 14 7.526599e+02 2.192000e+02 +2 14 6.170100e+02 1.575600e+02 +6 14 7.050100e+02 1.142800e+02 +12 14 -2.832900e+02 -4.596200e+02 +16 14 9.259500e+02 3.933000e+02 +17 14 -1.182130e+03 5.723101e+02 +0 15 1.592220e+03 4.869000e+02 +1 15 7.154099e+02 5.452200e+02 +3 15 6.106200e+02 6.356200e+02 +6 15 7.436500e+02 3.359800e+02 +16 15 9.815601e+02 5.467300e+02 +0 16 1.592220e+03 4.869000e+02 +1 16 7.154099e+02 5.452200e+02 +2 16 5.727600e+02 4.472300e+02 +3 16 6.106200e+02 6.356200e+02 +6 16 7.436500e+02 3.359800e+02 +7 16 8.869099e+02 5.749100e+02 +12 16 -2.558300e+02 -2.634700e+02 +16 16 9.815601e+02 5.467300e+02 +17 16 -1.291750e+03 1.028630e+03 +0 17 4.639700e+02 4.582200e+02 +1 17 -1.101980e+03 7.911500e+02 +2 17 -3.668400e+02 4.246500e+02 +4 17 8.366201e+02 4.717300e+02 +5 17 3.506200e+02 8.901300e+02 +7 17 1.870300e+02 5.317600e+02 +8 17 -8.678000e+02 6.906100e+02 +9 17 -3.886100e+02 4.586000e+02 +11 17 2.659600e+02 3.888400e+02 +18 17 -5.132600e+02 1.684199e+02 +20 17 -4.352900e+02 -5.140002e+01 +0 18 1.101110e+03 2.966200e+02 +1 18 -2.068900e+02 2.133700e+02 +4 18 1.288590e+03 4.486500e+02 +5 18 9.537900e+02 9.055699e+02 +6 18 1.500800e+02 9.869000e+01 +8 18 2.477300e+02 3.635701e+02 +13 18 -1.198570e+03 1.023260e+03 +16 18 6.780300e+02 4.588800e+02 +0 19 1.101110e+03 2.966200e+02 +1 19 -2.068900e+02 2.133700e+02 +4 19 1.288590e+03 4.486500e+02 +5 19 9.537900e+02 9.055699e+02 +8 19 2.477300e+02 3.635701e+02 +11 19 4.317700e+02 3.745000e+02 +16 19 6.780300e+02 4.588800e+02 +0 20 1.123840e+03 1.728600e+02 +1 20 -1.642900e+02 1.791998e+01 +4 20 1.298780e+03 3.626500e+02 +8 20 2.761200e+02 1.820400e+02 +0 21 1.155680e+03 1.497200e+02 +1 21 -1.165500e+02 -2.256000e+01 +4 21 1.320770e+03 3.470400e+02 +6 21 2.032300e+02 -6.292999e+01 +8 21 3.213700e+02 1.464800e+02 +9 21 -1.158199e+02 2.854399e+02 +10 21 -6.878003e+01 -3.699500e+02 +12 21 -6.329000e+02 -4.476700e+02 +13 21 -1.005330e+03 5.326000e+02 +16 21 7.129200e+02 3.672800e+02 +0 22 1.132120e+03 1.686699e+02 +1 22 -1.522500e+02 1.078998e+01 +4 22 1.304230e+03 3.595601e+02 +5 22 9.861699e+02 7.976100e+02 +6 22 1.788500e+02 -3.932001e+01 +8 22 2.880000e+02 1.758600e+02 +12 22 -6.514300e+02 -4.312900e+02 +0 23 1.100680e+03 3.059299e+02 +1 23 -2.072500e+02 2.277100e+02 +4 23 1.288470e+03 4.546799e+02 +5 23 9.523201e+02 9.141400e+02 +6 23 1.502600e+02 1.086800e+02 +8 23 2.474200e+02 3.771200e+02 +9 23 -1.841600e+02 4.569900e+02 +11 23 4.315699e+02 3.844800e+02 +13 23 -1.198440e+03 1.052400e+03 +16 23 6.781899e+02 4.642400e+02 +20 23 -3.165601e+02 -6.017004e+01 +0 24 1.648780e+03 4.902300e+02 +1 24 7.979600e+02 5.447600e+02 +2 24 6.276899e+02 4.471600e+02 +3 24 6.911000e+02 6.331300e+02 +12 24 -2.213700e+02 -2.647200e+02 +17 24 -1.205760e+03 1.023610e+03 +0 25 8.543899e+02 1.603201e+02 +1 25 -4.321000e+02 7.002002e+01 +4 25 1.076260e+03 3.208800e+02 +5 25 6.989200e+02 7.272100e+02 +6 25 -1.120900e+02 1.969000e+01 +7 25 3.940300e+02 3.367600e+02 +9 25 -1.819500e+02 2.254500e+02 +10 25 -1.341200e+02 -3.920699e+02 +12 25 -7.326100e+02 -4.937100e+02 +13 25 -1.286680e+03 4.718900e+02 +20 25 -3.239000e+02 -1.789399e+02 +0 26 8.192100e+02 1.816300e+02 +1 26 -4.825900e+02 1.157000e+02 +3 26 -5.284800e+02 2.201400e+02 +4 26 1.053400e+03 3.323800e+02 +5 26 6.661500e+02 7.382700e+02 +6 26 -1.543400e+02 5.332001e+01 +7 26 3.762600e+02 3.514299e+02 +0 27 7.863999e+02 1.025000e+01 +1 27 -5.346900e+02 -2.022700e+02 +6 27 -2.103800e+02 -1.644900e+02 +7 27 3.605601e+02 2.231500e+02 +10 27 -1.549700e+02 -4.925400e+02 +11 27 4.297500e+02 1.859003e+01 +13 27 -1.390040e+03 2.197998e+01 +18 27 -4.029000e+02 -7.043005e+01 +0 28 8.000100e+02 2.193005e+01 +1 28 -5.120200e+02 -1.878300e+02 +4 28 1.037970e+03 2.364399e+02 +0 29 8.144399e+02 1.230100e+02 +1 29 -4.883700e+02 8.150024e+00 +4 29 1.048430e+03 2.964500e+02 +5 29 6.656700e+02 6.912400e+02 +6 29 -1.681300e+02 -1.741998e+01 +7 29 3.761500e+02 3.050601e+02 +9 29 -1.930100e+02 1.831500e+02 +11 29 4.445000e+02 1.207800e+02 +13 29 -1.327880e+03 3.504299e+02 +18 29 -3.916000e+02 -4.540039e+00 +0 30 8.776599e+02 1.648700e+02 +1 30 -4.024100e+02 6.665991e+01 +3 30 -4.680600e+02 1.684900e+02 +4 30 1.093540e+03 3.277300e+02 +5 30 7.195601e+02 7.368900e+02 +7 30 4.030300e+02 3.377200e+02 +8 30 -1.540300e+02 1.922800e+02 +0 31 6.947900e+02 2.345200e+02 +1 31 -6.731200e+02 2.531799e+02 +2 31 -2.115000e+02 1.622600e+02 +3 31 -6.870000e+02 3.740601e+02 +4 31 9.726399e+02 3.549199e+02 +5 31 5.563101e+02 7.570900e+02 +6 31 -3.178400e+02 1.563700e+02 +7 31 3.134500e+02 3.799700e+02 +9 31 -2.556100e+02 2.713900e+02 +12 31 -8.036600e+02 -4.554000e+02 +13 31 -1.536950e+03 6.698201e+02 +18 31 -4.296400e+02 5.195996e+01 +0 32 6.947900e+02 2.345200e+02 +1 32 -6.731200e+02 2.531799e+02 +2 32 -2.115000e+02 1.622600e+02 +3 32 -6.870000e+02 3.740601e+02 +4 32 9.726399e+02 3.549199e+02 +5 32 5.563101e+02 7.570900e+02 +6 32 -3.178400e+02 1.563700e+02 +7 32 3.134500e+02 3.799700e+02 +9 32 -2.556100e+02 2.713900e+02 +12 32 -8.036600e+02 -4.554000e+02 +13 32 -1.536950e+03 6.698201e+02 +18 32 -4.296400e+02 5.195996e+01 +0 33 8.340400e+02 1.051000e+02 +1 33 -4.649301e+02 -2.944995e+01 +4 33 1.062990e+03 2.874099e+02 +5 33 6.873600e+02 6.812800e+02 +6 33 -1.402400e+02 -4.740997e+01 +7 33 3.818500e+02 2.944500e+02 +10 33 -1.425000e+02 -4.279200e+02 +11 33 4.408500e+02 1.093700e+02 +12 33 -7.458200e+02 -5.360500e+02 +13 33 -1.332630e+03 3.088101e+02 +20 33 -3.326801e+02 -2.076400e+02 +0 34 7.704800e+02 1.192700e+02 +1 34 -5.543200e+02 1.084003e+01 +2 34 -1.657600e+02 2.953998e+01 +3 34 -5.802800e+02 1.126100e+02 +6 34 -2.230500e+02 -1.519000e+01 +7 34 3.536801e+02 3.004000e+02 +9 34 -2.148600e+02 1.738600e+02 +10 34 -1.596300e+02 -4.226700e+02 +11 34 4.246700e+02 1.125300e+02 +12 34 -7.679500e+02 -5.324100e+02 +18 34 -4.056600e+02 -9.589966e+00 +20 34 -3.431100e+02 -2.061200e+02 +0 35 8.994900e+02 1.088500e+02 +1 35 -3.694000e+02 -3.418005e+01 +2 35 -1.162700e+02 2.721002e+01 +3 35 -4.443400e+02 5.996002e+01 +4 35 1.103020e+03 2.924500e+02 +5 35 7.441000e+02 6.948500e+02 +8 35 -1.195700e+02 1.023000e+02 +9 35 -1.617400e+02 1.814399e+02 +11 35 4.694100e+02 1.196400e+02 +12 35 -7.153900e+02 -5.273900e+02 +13 35 -1.215740e+03 3.218201e+02 +18 35 -3.699000e+02 -5.349976e+00 +20 35 -3.134600e+02 -2.022300e+02 +0 36 8.749800e+02 1.114800e+02 +1 36 -4.068500e+02 -2.476001e+01 +4 36 1.089140e+03 2.936699e+02 +0 37 8.857700e+02 2.163600e+02 +1 37 -3.929900e+02 1.674500e+02 +3 37 -4.683100e+02 2.702400e+02 +4 37 1.101020e+03 3.579600e+02 +5 37 7.235900e+02 7.774200e+02 +7 37 4.060300e+02 3.816200e+02 +8 37 -1.373200e+02 2.686600e+02 +13 37 -1.256930e+03 6.553300e+02 +18 37 -3.781899e+02 5.880005e+01 +20 37 -3.199500e+02 -1.469600e+02 +0 38 6.603501e+02 2.414199e+02 +1 38 -7.323900e+02 2.776699e+02 +2 38 -2.242600e+02 1.664500e+02 +3 38 -7.361300e+02 4.021899e+02 +4 38 9.512900e+02 3.565000e+02 +5 38 5.259500e+02 7.557000e+02 +6 38 -3.669800e+02 1.748500e+02 +7 38 2.969600e+02 3.829000e+02 +9 38 -2.697800e+02 2.731400e+02 +10 38 -2.013600e+02 -3.487200e+02 +11 38 3.765200e+02 2.089400e+02 +12 38 -8.169700e+02 -4.535400e+02 +13 38 -1.588930e+03 6.843600e+02 +18 38 -4.398300e+02 5.348999e+01 +20 38 -3.725000e+02 -1.522900e+02 +0 39 9.779700e+02 2.196300e+02 +1 39 -2.785601e+02 1.395701e+02 +4 39 1.171040e+03 3.711799e+02 +5 39 8.113000e+02 8.017100e+02 +8 39 2.173999e+01 2.685601e+02 +16 39 6.283900e+02 3.902800e+02 +0 40 7.493201e+02 2.550200e+02 +1 40 -5.843200e+02 2.799099e+02 +2 40 -1.818400e+02 1.891600e+02 +4 40 1.008850e+03 3.699800e+02 +5 40 5.989301e+02 7.821799e+02 +6 40 -2.398100e+02 1.722100e+02 +7 40 3.414600e+02 3.973201e+02 +10 40 -1.700300e+02 -3.356899e+02 +11 40 4.111801e+02 2.303200e+02 +12 40 -7.781800e+02 -4.363300e+02 +13 40 -1.445900e+03 7.363300e+02 +20 40 -3.489800e+02 -1.408300e+02 +0 41 1.150200e+03 2.032200e+02 +1 41 -1.250300e+02 6.676001e+01 +3 41 -3.188700e+02 1.427800e+02 +6 41 1.992500e+02 -1.830017e+00 +8 41 3.152700e+02 2.281800e+02 +9 41 -1.255900e+02 3.388000e+02 +11 41 4.915800e+02 2.742500e+02 +13 41 -1.024780e+03 7.059600e+02 +0 42 6.405300e+02 7.218005e+01 +1 42 -7.736200e+02 -6.221997e+01 +2 42 -2.327600e+02 -3.556000e+01 +4 42 9.372000e+02 2.586000e+02 +5 42 5.267800e+02 6.256100e+02 +6 42 -4.066300e+02 -5.610999e+01 +7 42 2.869100e+02 2.596799e+02 +10 42 -2.077500e+02 -4.594100e+02 +11 42 3.703400e+02 5.715997e+01 +13 42 -1.626730e+03 1.816100e+02 +18 42 -4.456000e+02 -4.480005e+01 +0 43 8.861201e+02 1.204301e+02 +1 43 -3.926700e+02 -1.096997e+01 +3 43 -4.647000e+02 8.834003e+01 +4 43 1.099270e+03 3.010701e+02 +5 43 7.327100e+02 7.028400e+02 +7 43 4.068400e+02 3.084000e+02 +8 43 -1.381800e+02 1.214800e+02 +9 43 -1.752500e+02 1.917000e+02 +11 43 4.577700e+02 1.292100e+02 +13 43 -1.257030e+03 3.594600e+02 +18 43 -3.785500e+02 1.170044e+00 +0 44 9.020701e+02 1.580200e+02 +1 44 -3.673199e+02 5.518994e+01 +2 44 -1.183600e+02 8.783997e+01 +3 44 -4.420500e+02 1.525200e+02 +4 44 1.110160e+03 3.236799e+02 +5 44 7.428700e+02 7.345000e+02 +6 44 -5.489001e+01 7.169983e+00 +7 44 4.163101e+02 3.377900e+02 +8 44 -1.122300e+02 1.785800e+02 +9 44 -1.656000e+02 2.297400e+02 +10 44 -1.187300e+02 -3.892200e+02 +12 44 -7.137100e+02 -4.895800e+02 +13 44 -1.221680e+03 4.764800e+02 +18 44 -3.713700e+02 2.468005e+01 +20 44 -3.139100e+02 -1.761801e+02 +0 45 8.336499e+02 1.729000e+02 +1 45 -4.646100e+02 9.726001e+01 +3 45 -5.165500e+02 2.002200e+02 +4 45 1.063120e+03 3.278401e+02 +5 45 6.798800e+02 7.338500e+02 +6 45 -1.393800e+02 4.070001e+01 +7 45 3.820800e+02 3.438000e+02 +9 45 -1.949399e+02 2.334900e+02 +10 45 -1.432000e+02 -3.846400e+02 +11 45 4.439700e+02 1.716600e+02 +12 45 -7.443500e+02 -4.872100e+02 +13 45 -1.325980e+03 5.080100e+02 +20 45 -3.308900e+02 -1.743900e+02 +0 46 8.383101e+02 1.950801e+02 +1 46 -4.546100e+02 1.392500e+02 +4 46 1.066810e+03 3.410601e+02 +5 46 6.816899e+02 7.519399e+02 +7 46 3.851600e+02 3.601300e+02 +10 46 -1.402200e+02 -3.693400e+02 +12 46 -7.407400e+02 -4.701400e+02 +13 46 -1.313570e+03 5.749600e+02 +18 46 -3.888101e+02 4.043994e+01 +20 46 -3.291000e+02 -1.623900e+02 +0 47 6.570901e+02 2.727100e+02 +1 47 -7.395900e+02 3.431000e+02 +2 47 -2.275400e+02 2.022600e+02 +4 47 9.498999e+02 3.743900e+02 +5 47 5.202100e+02 7.795701e+02 +7 47 2.952900e+02 4.041000e+02 +9 47 -2.717100e+02 3.003500e+02 +10 47 -2.037500e+02 -3.291801e+02 +11 47 3.741700e+02 2.343900e+02 +12 47 -8.176100e+02 -4.325500e+02 +13 47 -1.593540e+03 7.737000e+02 +18 47 -4.412100e+02 6.935999e+01 +20 47 -3.732300e+02 -1.381400e+02 +0 48 6.193999e+02 1.648101e+02 +1 48 -8.088700e+02 1.322600e+02 +2 48 -2.512200e+02 7.306000e+01 +3 48 -8.017800e+02 2.515300e+02 +4 48 9.253899e+02 3.102100e+02 +5 48 5.014500e+02 6.919500e+02 +6 48 -4.310400e+02 7.935999e+01 +7 48 2.747700e+02 3.249900e+02 +9 48 -2.908900e+02 1.973800e+02 +10 48 -2.189100e+02 -4.003900e+02 +13 48 -1.670880e+03 4.531599e+02 +18 48 -4.547600e+02 6.310059e+00 +20 48 -3.852000e+02 -1.926100e+02 +0 49 8.908899e+02 1.604000e+02 +1 49 -3.858400e+02 6.139001e+01 +3 49 -4.595400e+02 1.594000e+02 +4 49 1.103150e+03 3.248500e+02 +5 49 7.327600e+02 7.344700e+02 +6 49 -6.759998e+01 1.295001e+01 +8 49 -1.310300e+02 1.831600e+02 +0 50 1.694560e+03 3.280200e+02 +1 50 1.198720e+03 3.744500e+02 +10 50 4.001399e+02 -3.166100e+02 +12 50 -1.513400e+02 -4.355000e+02 +17 50 -7.746400e+02 6.413000e+02 +0 51 7.553101e+02 8.714001e+01 +1 51 -5.787600e+02 -5.009998e+01 +3 51 -6.010700e+02 5.107001e+01 +4 51 1.009450e+03 2.721899e+02 +5 51 6.195800e+02 6.542100e+02 +6 51 -2.451300e+02 -5.490002e+01 +0 52 8.976399e+02 1.822200e+02 +1 52 -3.738101e+02 1.011000e+02 +4 52 1.108220e+03 3.377600e+02 +5 52 7.368700e+02 7.540300e+02 +8 52 -1.192700e+02 2.165600e+02 +0 53 7.607600e+02 2.182800e+02 +1 53 -5.671200e+02 2.064500e+02 +2 53 -1.736300e+02 1.460900e+02 +5 53 6.115200e+02 7.564399e+02 +6 53 -2.288800e+02 1.198600e+02 +9 53 -2.223500e+02 2.636200e+02 +10 53 -1.651200e+02 -3.585601e+02 +11 53 4.179000e+02 1.994900e+02 +12 53 -7.723900e+02 -4.619900e+02 +0 54 1.100680e+03 3.059299e+02 +1 54 -2.072500e+02 2.277100e+02 +4 54 1.288470e+03 4.546799e+02 +5 54 9.523201e+02 9.141400e+02 +6 54 1.502600e+02 1.086800e+02 +8 54 2.474200e+02 3.771200e+02 +11 54 4.315699e+02 3.844800e+02 +16 54 6.781899e+02 4.642400e+02 +20 54 -3.165100e+02 -5.515002e+01 +0 55 1.581920e+03 2.001300e+02 +1 55 1.003270e+03 1.482200e+02 +2 55 7.658400e+02 8.763000e+01 +3 55 1.064730e+03 2.566500e+02 +5 55 1.195610e+03 8.228101e+02 +6 55 8.623300e+02 6.559003e+01 +7 55 9.131101e+02 3.379700e+02 +8 55 8.408199e+02 2.462500e+02 +16 55 9.733600e+02 3.580000e+02 +17 55 -9.391000e+02 4.591699e+02 +0 56 1.585690e+03 4.793600e+02 +1 56 7.066899e+02 5.331799e+02 +2 56 5.652900e+02 4.401400e+02 +3 56 6.015900e+02 6.236500e+02 +12 56 -2.598101e+02 -2.689600e+02 +16 56 9.780699e+02 5.430000e+02 +0 57 1.597070e+03 4.733700e+02 +1 57 7.217000e+02 5.229800e+02 +2 57 5.779100e+02 4.318900e+02 +3 57 6.169000e+02 6.129000e+02 +7 57 8.902600e+02 5.648201e+02 +12 57 -2.527600e+02 -2.743400e+02 +17 57 -1.284400e+03 1.003560e+03 +0 58 6.042900e+02 3.663401e+02 +1 58 -8.261500e+02 5.504000e+02 +3 58 -8.205800e+02 6.993000e+02 +4 58 9.183601e+02 4.254900e+02 +5 58 4.680300e+02 8.426200e+02 +7 58 2.689700e+02 4.704099e+02 +8 58 -6.280100e+02 5.317100e+02 +9 58 -2.981600e+02 3.829800e+02 +10 58 -2.232700e+02 -2.706000e+02 +11 58 3.503400e+02 3.117700e+02 +12 58 -8.405300e+02 -3.658900e+02 +18 58 -4.566200e+02 1.205400e+02 +0 59 4.523601e+02 4.540100e+02 +1 59 -1.127050e+03 7.892100e+02 +2 59 -3.765400e+02 4.142900e+02 +4 59 8.298701e+02 4.682700e+02 +5 59 3.421899e+02 8.845601e+02 +7 59 1.802700e+02 5.283000e+02 +8 59 -8.881900e+02 6.859000e+02 +9 59 -3.964200e+02 4.508301e+02 +10 59 -2.957300e+02 -2.170400e+02 +11 59 2.592400e+02 3.798500e+02 +12 59 -9.220800e+02 -3.115601e+02 +18 59 -5.179800e+02 1.654500e+02 +20 59 -4.392000e+02 -5.581006e+01 +0 60 1.581680e+03 2.332400e+02 +1 60 1.002040e+03 2.091500e+02 +2 60 7.664301e+02 1.215400e+02 +3 60 1.064890e+03 3.200300e+02 +5 60 1.193140e+03 8.481801e+02 +6 60 8.602700e+02 1.108200e+02 +8 60 8.390400e+02 2.973800e+02 +12 60 -2.152100e+02 -4.882000e+02 +17 60 -9.391600e+02 5.102500e+02 +0 61 9.836399e+02 2.793101e+02 +1 61 -2.980200e+02 2.352900e+02 +6 61 4.053003e+01 1.222700e+02 +16 61 6.251100e+02 4.300100e+02 +0 62 7.485701e+02 3.739199e+02 +1 62 -6.239300e+02 4.802200e+02 +6 62 -2.313600e+02 3.022800e+02 +7 62 3.172200e+02 4.978201e+02 +8 62 -3.516900e+02 5.231799e+02 +0 63 4.523601e+02 4.540100e+02 +1 63 -1.127050e+03 7.892100e+02 +2 63 -3.765400e+02 4.142900e+02 +4 63 8.298701e+02 4.682700e+02 +5 63 3.421899e+02 8.845601e+02 +7 63 1.802700e+02 5.283000e+02 +9 63 -3.964200e+02 4.508301e+02 +10 63 -2.957300e+02 -2.170400e+02 +12 63 -9.220800e+02 -3.115601e+02 +18 63 -5.179800e+02 1.654500e+02 +20 63 -4.392000e+02 -5.581006e+01 +0 64 8.982700e+02 8.410999e+01 +1 64 -3.740900e+02 -7.891003e+01 +2 64 -1.199500e+02 1.039978e+00 +3 64 -4.463900e+02 1.488000e+01 +4 64 1.106590e+03 2.770300e+02 +5 64 7.461300e+02 6.746100e+02 +7 64 4.139800e+02 2.831599e+02 +8 64 -1.196500e+02 6.371997e+01 +10 64 -1.199399e+02 -4.377700e+02 +11 64 4.661600e+02 9.957001e+01 +12 64 -7.171700e+02 -5.442400e+02 +18 64 -3.734200e+02 -1.864001e+01 +20 64 -3.156600e+02 -2.136500e+02 +0 65 8.927900e+02 9.218005e+01 +1 65 -3.832400e+02 -6.422998e+01 +2 65 -1.246600e+02 9.500000e+00 +3 65 -4.543400e+02 3.013000e+01 +6 65 -6.790002e+01 -7.490997e+01 +7 65 4.106000e+02 2.880701e+02 +8 65 -1.285400e+02 7.696002e+01 +10 65 -1.228600e+02 -4.332500e+02 +11 65 4.622500e+02 1.054400e+02 +12 65 -7.204600e+02 -5.396801e+02 +13 65 -1.243340e+03 2.777700e+02 +18 65 -3.756300e+02 -1.500000e+01 +0 66 9.130701e+02 9.467004e+01 +1 66 -3.530200e+02 -6.243005e+01 +4 66 1.117200e+03 2.855300e+02 +5 66 7.584399e+02 6.860200e+02 +8 66 -9.435999e+01 7.965997e+01 +0 67 7.858799e+02 8.968005e+01 +1 67 -5.320200e+02 -4.910999e+01 +3 67 -5.635100e+02 5.131000e+01 +4 67 1.029610e+03 2.750100e+02 +5 67 6.453400e+02 6.607900e+02 +6 67 -2.043400e+02 -5.770001e+01 +13 67 -1.387550e+03 2.555500e+02 +0 68 1.160380e+03 1.679299e+02 +1 68 -1.076000e+02 7.979980e+00 +3 68 -2.991300e+02 8.777002e+01 +6 68 2.095200e+02 -4.216998e+01 +13 68 -9.844500e+02 5.928201e+02 +0 69 8.115400e+02 2.146997e+01 +1 69 -4.967200e+02 -1.859301e+02 +3 69 -5.370000e+02 -9.226001e+01 +6 69 -1.740000e+02 -1.530500e+02 +13 69 -1.357270e+03 5.300000e+01 +0 70 9.130400e+02 7.044995e+01 +1 70 -3.548199e+02 -1.059600e+02 +3 70 -4.314300e+02 -1.365002e+01 +8 70 -9.447998e+01 4.244000e+01 +13 70 -1.210710e+03 2.181599e+02 +0 71 9.176299e+02 7.318005e+01 +1 71 -3.488400e+02 -1.024200e+02 +3 71 -4.271200e+02 -1.000000e+01 +8 71 -8.665997e+01 4.653998e+01 +13 71 -1.203320e+03 2.238301e+02 +0 72 5.417300e+02 2.996699e+02 +1 72 -9.482300e+02 4.401799e+02 +2 72 -2.899800e+02 2.255200e+02 +4 72 8.806001e+02 3.826400e+02 +5 72 4.259600e+02 7.808101e+02 +7 72 2.366000e+02 4.173101e+02 +9 72 -3.265601e+02 3.119099e+02 +10 72 -2.471801e+02 -3.180500e+02 +11 72 3.273199e+02 2.430400e+02 +12 72 -8.695500e+02 -4.235200e+02 +18 72 -4.759301e+02 7.696997e+01 +0 73 6.002800e+02 8.131995e+01 +1 73 -8.492700e+02 -4.051001e+01 +4 73 9.128401e+02 2.623500e+02 +5 73 4.929600e+02 6.262000e+02 +0 74 1.566990e+03 2.885000e+02 +1 74 9.718401e+02 3.083700e+02 +2 74 7.479700e+02 1.807300e+02 +5 74 1.181790e+03 8.896200e+02 +6 74 8.401899e+02 1.819300e+02 +7 74 9.044800e+02 3.972100e+02 +8 74 8.211600e+02 3.799800e+02 +16 74 9.663600e+02 4.056799e+02 +17 74 -9.603900e+02 6.014900e+02 +0 75 5.315701e+02 3.352600e+02 +1 75 -9.696400e+02 5.129500e+02 +2 75 -3.116400e+02 2.710600e+02 +4 75 8.744700e+02 4.039000e+02 +5 75 4.139000e+02 8.064900e+02 +6 75 -5.524200e+02 3.431899e+02 +7 75 2.284600e+02 4.434399e+02 +8 75 -7.569200e+02 4.875601e+02 +9 75 -3.431000e+02 3.452900e+02 +10 75 -2.557700e+02 -2.934900e+02 +11 75 3.115500e+02 2.779900e+02 +12 75 -8.834600e+02 -3.977200e+02 +18 75 -4.875500e+02 9.454004e+01 +20 75 -4.129200e+02 -1.160300e+02 +0 76 5.538000e+02 3.613000e+02 +1 76 -9.225700e+02 5.572300e+02 +2 76 -2.899700e+02 3.006300e+02 +4 76 8.885000e+02 4.177900e+02 +7 76 2.407400e+02 4.624700e+02 +8 76 -7.196300e+02 5.238400e+02 +9 76 -3.253199e+02 3.702000e+02 +10 76 -2.453000e+02 -2.767900e+02 +12 76 -8.675800e+02 -3.775800e+02 +0 77 5.305601e+02 3.700500e+02 +1 77 -9.682100e+02 5.857900e+02 +2 77 -3.139200e+02 3.098700e+02 +5 77 4.102100e+02 8.327400e+02 +9 77 -3.435400e+02 3.769900e+02 +20 77 -4.098199e+02 -9.650000e+01 +0 78 4.874700e+02 4.016000e+02 +1 78 -1.055950e+03 6.688300e+02 +2 78 -3.390300e+02 3.506600e+02 +5 78 3.712300e+02 8.491899e+02 +7 78 2.040300e+02 4.911300e+02 +8 78 -8.361500e+02 5.980601e+02 +9 78 -3.662500e+02 4.042000e+02 +10 78 -2.743600e+02 -2.509900e+02 +11 78 2.882600e+02 3.356300e+02 +12 78 -9.000200e+02 -3.500300e+02 +0 79 5.711001e+02 7.940002e+01 +1 79 -9.015900e+02 -3.571997e+01 +3 79 -8.777800e+02 7.570001e+01 +4 79 8.957900e+02 2.599199e+02 +5 79 4.707500e+02 6.208300e+02 +7 79 2.527900e+02 2.617800e+02 +0 80 6.523601e+02 8.526001e+01 +1 80 -7.520200e+02 -3.681995e+01 +2 80 -2.210500e+02 -2.063000e+01 +3 80 -7.468700e+02 6.959003e+01 +4 80 9.446201e+02 2.672400e+02 +5 80 5.348300e+02 6.377800e+02 +6 80 -3.906400e+02 -3.947998e+01 +7 80 2.926000e+02 2.708700e+02 +9 80 -2.645400e+02 1.286699e+02 +10 80 -1.984500e+02 -4.519000e+02 +11 80 3.797600e+02 6.909003e+01 +18 80 -4.379800e+02 -3.697998e+01 +20 80 -3.714600e+02 -2.300200e+02 +0 81 1.581920e+03 2.001300e+02 +1 81 1.003270e+03 1.482200e+02 +2 81 7.658400e+02 8.763000e+01 +3 81 1.064730e+03 2.566500e+02 +6 81 8.623300e+02 6.559003e+01 +7 81 9.131101e+02 3.379700e+02 +8 81 8.408199e+02 2.462500e+02 +17 81 -9.391000e+02 4.591699e+02 +0 82 7.481101e+02 2.240801e+02 +1 82 -5.897500e+02 2.196899e+02 +2 82 -1.869700e+02 1.551800e+02 +3 82 -6.180800e+02 3.352800e+02 +4 82 1.007880e+03 3.516400e+02 +5 82 6.011899e+02 7.581100e+02 +6 82 -2.447600e+02 1.284200e+02 +7 82 3.387800e+02 3.763101e+02 +10 82 -1.724399e+02 -3.547100e+02 +11 82 4.076700e+02 2.050600e+02 +12 82 -7.807300e+02 -4.576300e+02 +13 82 -1.459380e+03 6.510400e+02 +18 82 -4.153600e+02 5.028003e+01 +20 82 -3.515200e+02 -1.545699e+02 +0 83 6.827800e+02 2.527900e+02 +1 83 -6.928100e+02 2.943700e+02 +2 83 -2.099600e+02 1.810000e+02 +4 83 9.664299e+02 3.645000e+02 +5 83 5.435800e+02 7.688900e+02 +6 83 -3.355600e+02 1.864200e+02 +7 83 3.088400e+02 3.916899e+02 +9 83 -2.571300e+02 2.856100e+02 +10 83 -1.926500e+02 -3.407800e+02 +11 83 3.871500e+02 2.208200e+02 +12 83 -8.051400e+02 -4.445800e+02 +13 83 -1.544110e+03 7.195000e+02 +18 83 -4.315400e+02 6.078003e+01 +20 83 -3.652700e+02 -1.455601e+02 +0 84 6.504600e+02 2.563700e+02 +1 84 -7.458900e+02 3.122000e+02 +2 84 -2.324600e+02 1.859000e+02 +4 84 9.454199e+02 3.648000e+02 +5 84 5.174301e+02 7.665400e+02 +7 84 2.908600e+02 3.931799e+02 +10 84 -2.060500e+02 -3.385500e+02 +11 84 3.693900e+02 2.231700e+02 +12 84 -8.222000e+02 -4.424399e+02 +13 84 -1.606230e+03 7.329200e+02 +20 84 -3.759800e+02 -1.447100e+02 +0 85 1.567610e+03 1.071400e+02 +1 85 9.798101e+02 -2.127002e+01 +2 85 7.510100e+02 -7.109985e+00 +4 85 1.486780e+03 2.776599e+02 +5 85 1.192720e+03 7.522600e+02 +8 85 8.213700e+02 1.041400e+02 +12 85 -2.248800e+02 -5.657300e+02 +16 85 9.648199e+02 3.099000e+02 +0 86 1.575280e+03 1.816799e+02 +1 86 9.916201e+02 1.141000e+02 +2 86 7.597200e+02 6.940002e+01 +3 86 1.050820e+03 2.206699e+02 +5 86 1.192700e+03 8.089299e+02 +8 86 8.325601e+02 2.187300e+02 +12 86 -2.196400e+02 -5.194100e+02 +17 86 -9.489500e+02 4.313201e+02 +0 87 5.695901e+02 1.728500e+02 +1 87 -9.021300e+02 1.593301e+02 +2 87 -2.755800e+02 7.785999e+01 +7 87 2.503700e+02 3.285400e+02 +9 87 -3.127300e+02 1.994900e+02 +11 87 3.361801e+02 1.378100e+02 +0 88 7.459700e+02 2.117500e+02 +1 88 -5.951300e+02 1.966000e+02 +2 88 -1.829000e+02 1.370100e+02 +4 88 1.005840e+03 3.448500e+02 +5 88 6.005400e+02 7.485400e+02 +6 88 -2.492700e+02 1.130500e+02 +7 88 3.388800e+02 3.667300e+02 +10 88 -1.721100e+02 -3.634100e+02 +11 88 4.095500e+02 1.930700e+02 +12 88 -7.811100e+02 -4.672800e+02 +13 88 -1.460570e+03 6.143000e+02 +18 88 -4.158500e+02 4.306006e+01 +20 88 -3.515900e+02 -1.609200e+02 +0 89 6.792300e+02 2.237000e+02 +1 89 -7.045500e+02 2.369900e+02 +2 89 -2.215300e+02 1.486800e+02 +3 89 -7.150700e+02 3.571300e+02 +4 89 9.634900e+02 3.479299e+02 +5 89 5.442600e+02 7.463101e+02 +6 89 -3.410400e+02 1.454700e+02 +7 89 3.041000e+02 3.719800e+02 +9 89 -2.651600e+02 2.615400e+02 +10 89 -1.976000e+02 -3.585300e+02 +11 89 3.800200e+02 1.960100e+02 +12 89 -8.118200e+02 -4.641801e+02 +13 89 -1.572050e+03 6.392000e+02 +18 89 -4.364600e+02 4.532996e+01 +20 89 -3.696899e+02 -1.590400e+02 +0 90 4.960200e+02 2.633700e+02 +1 90 -1.046320e+03 3.694700e+02 +2 90 -3.359200e+02 1.843500e+02 +4 90 8.536399e+02 3.614299e+02 +5 90 3.951700e+02 7.476300e+02 +6 90 -6.135000e+02 2.474100e+02 +7 90 2.070400e+02 3.914199e+02 +8 90 -8.205300e+02 3.727400e+02 +9 90 -3.620000e+02 2.779900e+02 +10 90 -2.730900e+02 -3.402900e+02 +11 90 2.901600e+02 2.127200e+02 +12 90 -9.003900e+02 -4.477600e+02 +18 90 -4.991800e+02 5.767993e+01 +20 90 -4.231300e+02 -1.482700e+02 +0 91 1.539850e+03 2.985901e+02 +1 91 9.158301e+02 3.234000e+02 +2 91 7.185100e+02 1.926900e+02 +3 91 9.680300e+02 4.346400e+02 +5 91 1.162960e+03 8.954800e+02 +7 91 8.880500e+02 4.059600e+02 +8 91 7.833800e+02 3.956600e+02 +16 91 9.533900e+02 4.117300e+02 +17 91 -1.013950e+03 6.203500e+02 +0 92 4.647500e+02 4.472400e+02 +1 92 -1.101500e+03 7.707200e+02 +2 92 -3.638700e+02 4.042100e+02 +4 92 8.374700e+02 4.644199e+02 +5 92 3.522000e+02 8.818400e+02 +7 92 1.892600e+02 5.222500e+02 +8 92 -8.675100e+02 6.748199e+02 +9 92 -3.863300e+02 4.443201e+02 +10 92 -2.885900e+02 -2.225699e+02 +11 92 2.685100e+02 3.732900e+02 +12 92 -9.149000e+02 -3.188300e+02 +18 92 -5.114100e+02 1.610500e+02 +20 92 -4.341300e+02 -5.956006e+01 +0 93 1.552760e+03 9.738000e+01 +1 93 9.455100e+02 -3.880005e+01 +2 93 7.324900e+02 -1.579999e+01 +3 93 9.988601e+02 6.800000e+01 +4 93 1.479430e+03 2.721500e+02 +5 93 1.184440e+03 7.438800e+02 +7 93 8.926599e+02 2.719600e+02 +8 93 8.016500e+02 8.941998e+01 +16 93 9.569399e+02 3.050100e+02 +17 93 -9.917300e+02 3.035601e+02 +0 94 1.518090e+03 1.944399e+02 +1 94 8.676899e+02 1.336699e+02 +2 94 6.886899e+02 8.701001e+01 +3 94 9.132500e+02 2.405300e+02 +6 94 7.674200e+02 5.415997e+01 +7 94 8.708101e+02 3.377400e+02 +8 94 7.547500e+02 2.364000e+02 +17 94 -1.060110e+03 4.607400e+02 +0 95 8.394099e+02 1.645400e+02 +1 95 -4.533900e+02 8.127002e+01 +2 95 -1.437700e+02 8.945996e+01 +3 95 -5.071200e+02 1.840000e+02 +4 95 1.066880e+03 3.230701e+02 +5 95 6.853101e+02 7.282000e+02 +6 95 -1.310200e+02 2.903998e+01 +7 95 3.861400e+02 3.379199e+02 +9 95 -1.899200e+02 2.260000e+02 +10 95 -1.387600e+02 -3.889500e+02 +11 95 4.456300e+02 1.629600e+02 +12 95 -7.391800e+02 -4.918300e+02 +13 95 -1.311550e+03 4.837900e+02 +18 95 -3.881500e+02 2.263000e+01 +20 95 -3.279900e+02 -1.779700e+02 +0 96 5.371299e+02 1.830500e+02 +1 96 -9.648500e+02 1.910100e+02 +2 96 -3.018400e+02 8.954999e+01 +4 96 8.767400e+02 3.172500e+02 +5 96 4.346700e+02 6.933101e+02 +6 96 -5.556100e+02 1.241500e+02 +9 96 -3.342500e+02 2.063700e+02 +10 96 -2.526500e+02 -3.917800e+02 +11 96 3.160900e+02 1.438200e+02 +12 96 -8.777000e+02 -5.067900e+02 +18 96 -4.820900e+02 1.151001e+01 +20 96 -4.089800e+02 -1.878800e+02 +0 97 7.363799e+02 2.049199e+02 +1 97 -6.133300e+02 1.845500e+02 +3 97 -6.431900e+02 2.984800e+02 +4 97 9.996001e+02 3.405801e+02 +5 97 5.945800e+02 7.418400e+02 +6 97 -2.628000e+02 1.045500e+02 +7 97 3.321400e+02 3.616599e+02 +9 97 -2.389399e+02 2.512700e+02 +10 97 -1.780500e+02 -3.683600e+02 +12 97 -7.879800e+02 -4.724399e+02 +13 97 -1.483660e+03 5.899700e+02 +18 97 -4.196400e+02 3.950000e+01 +20 97 -3.555699e+02 -1.645900e+02 +0 98 1.494560e+03 2.698700e+02 +1 98 7.631101e+02 2.524099e+02 +2 98 6.232400e+02 1.771900e+02 +3 98 7.655800e+02 3.573900e+02 +6 98 7.110000e+02 1.379900e+02 +7 98 8.498401e+02 3.961200e+02 +17 98 -1.170410e+03 6.023600e+02 +0 99 4.534199e+02 3.830100e+02 +1 99 -1.129620e+03 6.360701e+02 +2 99 -3.781300e+02 3.293400e+02 +4 99 8.298401e+02 4.275601e+02 +5 99 3.506801e+02 8.314200e+02 +6 99 -6.665500e+02 4.305701e+02 +7 99 1.800000e+02 4.769500e+02 +8 99 -8.874200e+02 5.689600e+02 +9 99 -3.998000e+02 3.872700e+02 +10 99 -2.972600e+02 -2.624100e+02 +11 99 2.580900e+02 3.170300e+02 +12 99 -9.264600e+02 -3.621899e+02 +18 99 -5.188000e+02 1.247600e+02 +20 99 -4.405601e+02 -9.057996e+01 +0 100 4.544900e+02 4.183700e+02 +1 100 -1.124990e+03 7.141899e+02 +2 100 -3.714500e+02 3.704100e+02 +4 100 8.311299e+02 4.471599e+02 +5 100 3.470800e+02 8.579900e+02 +7 100 1.825699e+02 5.017600e+02 +8 100 -8.875900e+02 6.283600e+02 +9 100 -3.915699e+02 4.171300e+02 +11 100 2.635200e+02 3.468800e+02 +12 100 -9.202400e+02 -3.385900e+02 +20 100 -4.373400e+02 -7.396997e+01 +0 101 5.116499e+02 4.354900e+02 +1 101 -1.004330e+03 7.264200e+02 +2 101 -3.252900e+02 3.872500e+02 +7 101 2.175800e+02 5.149600e+02 +9 101 -3.553199e+02 4.336100e+02 +10 101 -2.652700e+02 -2.298800e+02 +11 101 2.992400e+02 3.630601e+02 +0 102 6.304199e+02 9.647998e+01 +1 102 -7.920000e+02 -1.059998e+01 +2 102 -2.413800e+02 -5.969971e+00 +3 102 -7.819800e+02 9.822998e+01 +4 102 9.318601e+02 2.719900e+02 +5 102 5.165200e+02 6.420701e+02 +6 102 -4.218100e+02 -1.964001e+01 +7 102 2.805699e+02 2.772100e+02 +9 102 -2.827000e+02 1.382500e+02 +10 102 -2.135000e+02 -4.435800e+02 +11 102 3.629000e+02 7.853003e+01 +13 102 -1.648270e+03 2.557400e+02 +18 102 -4.509399e+02 -3.093005e+01 +0 103 5.596799e+02 1.032500e+02 +1 103 -9.235200e+02 1.715997e+01 +2 103 -2.822300e+02 -2.330017e+00 +3 103 -9.001500e+02 1.308000e+02 +4 103 8.890901e+02 2.731400e+02 +5 103 4.596700e+02 6.366600e+02 +7 103 2.441801e+02 2.795300e+02 +9 103 -3.176700e+02 1.372000e+02 +10 103 -2.410400e+02 -4.420300e+02 +11 103 3.309700e+02 7.753003e+01 +20 103 -4.013600e+02 -2.251801e+02 +0 104 7.479299e+02 1.155300e+02 +1 104 -5.928900e+02 5.859985e+00 +2 104 -1.841200e+02 2.398999e+01 +3 104 -6.174700e+02 1.097900e+02 +4 104 1.005340e+03 2.886599e+02 +5 104 6.110800e+02 6.748900e+02 +7 104 3.400200e+02 2.966300e+02 +11 104 4.104500e+02 1.072700e+02 +0 105 1.583720e+03 1.756899e+02 +1 105 8.692700e+02 8.348999e+01 +0 106 1.583720e+03 1.756899e+02 +1 106 8.692700e+02 8.348999e+01 +0 107 5.749900e+02 1.604199e+02 +1 107 -8.908200e+02 1.344199e+02 +2 107 -2.721100e+02 6.757001e+01 +4 107 8.988501e+02 3.060100e+02 +5 107 4.653900e+02 6.816700e+02 +10 107 -2.340400e+02 -4.037600e+02 +11 107 3.380500e+02 1.321800e+02 +20 107 -3.960100e+02 -1.959000e+02 +0 108 1.532160e+03 1.775901e+02 +1 108 8.990300e+02 1.049500e+02 +2 108 7.064301e+02 6.854999e+01 +3 108 9.482400e+02 2.121699e+02 +4 108 1.471490e+03 3.192800e+02 +5 108 1.167130e+03 8.020701e+02 +7 108 8.800801e+02 3.258101e+02 +8 108 7.741300e+02 2.114100e+02 +12 108 -2.470900e+02 -5.185699e+02 +16 108 9.471200e+02 3.480500e+02 +17 108 -1.031870e+03 4.319600e+02 +0 109 5.426699e+02 1.648000e+02 +1 109 -9.537100e+02 1.508500e+02 +2 109 -2.951800e+02 7.012000e+01 +3 109 -9.311900e+02 2.775801e+02 +4 109 8.797600e+02 3.069800e+02 +5 109 4.400900e+02 6.797900e+02 +6 109 -5.490400e+02 9.684998e+01 +9 109 -3.288700e+02 1.919800e+02 +10 109 -2.492200e+02 -4.023199e+02 +11 109 3.210400e+02 1.299200e+02 +12 109 -8.754100e+02 -5.165300e+02 +18 109 -4.795500e+02 3.150024e+00 +0 110 1.587360e+03 2.404199e+02 +1 110 1.013710e+03 2.206300e+02 +2 110 7.724500e+02 1.292800e+02 +3 110 1.077510e+03 3.308500e+02 +6 110 8.691500e+02 1.185000e+02 +8 110 8.477000e+02 3.086400e+02 +17 110 -9.282600e+02 5.205200e+02 +0 111 5.495300e+02 2.556000e+02 +1 111 -9.367300e+02 3.423101e+02 +2 111 -2.927200e+02 1.827400e+02 +4 111 8.845100e+02 3.596599e+02 +5 111 4.359301e+02 7.495701e+02 +7 111 2.383199e+02 3.897000e+02 +8 111 -7.291400e+02 3.583600e+02 +9 111 -3.279301e+02 2.784299e+02 +10 111 -2.473500e+02 -3.411801e+02 +11 111 3.222200e+02 2.135200e+02 +12 111 -8.713800e+02 -4.481400e+02 +0 112 1.598770e+03 3.001500e+02 +1 112 1.031510e+03 3.273101e+02 +2 112 7.827800e+02 1.892100e+02 +3 112 1.092720e+03 4.391400e+02 +7 112 9.250100e+02 4.036100e+02 +12 112 -2.040200e+02 -4.469000e+02 +17 112 -9.140700e+02 6.126799e+02 +0 113 1.516860e+03 2.973301e+02 +1 113 8.626399e+02 3.194099e+02 +2 113 6.866899e+02 1.946700e+02 +3 113 9.049600e+02 4.295701e+02 +6 113 7.684399e+02 1.903700e+02 +7 113 8.709199e+02 4.063700e+02 +16 113 9.408101e+02 4.128900e+02 +17 113 -1.063420e+03 6.248800e+02 +0 114 1.558390e+03 3.050400e+02 +1 114 9.512900e+02 3.357400e+02 +2 114 7.379800e+02 1.978800e+02 +3 114 1.009040e+03 4.470200e+02 +4 114 1.488590e+03 3.924500e+02 +5 114 1.174790e+03 9.016700e+02 +7 114 8.996399e+02 4.087900e+02 +8 114 8.084700e+02 4.056799e+02 +17 114 -9.813700e+02 6.270200e+02 +0 115 1.581740e+03 3.100601e+02 +1 115 9.917900e+02 3.435000e+02 +2 115 7.612600e+02 2.000500e+02 +3 115 1.052370e+03 4.562700e+02 +6 115 8.583199e+02 2.092600e+02 +16 115 9.741500e+02 4.162800e+02 +17 115 -9.451400e+02 6.298301e+02 +0 116 1.584820e+03 3.108000e+02 +1 116 1.007150e+03 3.466899e+02 +2 116 7.690601e+02 2.010400e+02 +3 116 1.069480e+03 4.592500e+02 +6 116 8.699399e+02 2.115800e+02 +7 116 9.167600e+02 4.109800e+02 +17 116 -9.323500e+02 6.308101e+02 +0 117 4.748999e+02 4.557600e+02 +1 117 -1.078980e+03 7.852800e+02 +2 117 -3.571200e+02 4.157300e+02 +4 117 8.430801e+02 4.694600e+02 +5 117 3.589600e+02 8.897800e+02 +7 117 1.938500e+02 5.294800e+02 +8 117 -8.487500e+02 6.869800e+02 +10 117 -2.840699e+02 -2.160900e+02 +11 117 2.735699e+02 3.821600e+02 +12 117 -9.081100e+02 -3.110300e+02 +18 117 -5.078400e+02 1.661799e+02 +20 117 -4.309200e+02 -5.456006e+01 +0 118 5.009199e+02 4.766599e+02 +1 118 -1.024320e+03 8.186700e+02 +2 118 -3.361800e+02 4.406799e+02 +4 118 8.582400e+02 4.827700e+02 +11 118 2.894399e+02 4.024700e+02 +0 119 5.692900e+02 1.116100e+02 +1 119 -9.035900e+02 3.206006e+01 +2 119 -2.744400e+02 5.099976e+00 +3 119 -8.821200e+02 1.455000e+02 +4 119 8.944099e+02 2.782500e+02 +5 119 4.654000e+02 6.447500e+02 +7 119 2.503000e+02 2.843101e+02 +10 119 -2.361801e+02 -4.376300e+02 +11 119 3.368500e+02 8.345001e+01 +12 119 -8.616500e+02 -5.556700e+02 +18 119 -4.692800e+02 -2.738000e+01 +20 119 -3.978600e+02 -2.215699e+02 +0 120 1.524680e+03 1.698000e+02 +1 120 8.821699e+02 8.995996e+01 +2 120 6.968000e+02 6.063000e+01 +3 120 9.295500e+02 1.960601e+02 +5 120 1.163210e+03 7.966200e+02 +6 120 7.763400e+02 2.285999e+01 +7 120 8.747700e+02 3.209700e+02 +12 120 -2.522000e+02 -5.234000e+02 +16 120 9.433400e+02 3.447100e+02 +17 120 -1.046510e+03 4.203000e+02 +0 121 1.574860e+03 1.772600e+02 +1 121 9.897500e+02 1.054000e+02 +2 121 7.579301e+02 6.422998e+01 +3 121 1.049430e+03 2.123301e+02 +6 121 8.504200e+02 3.356000e+01 +17 121 -9.508400e+02 4.235701e+02 +0 122 6.715400e+02 1.985801e+02 +1 122 -7.187600e+02 1.856200e+02 +2 122 -2.278900e+02 1.174700e+02 +5 122 5.401000e+02 7.263900e+02 +7 122 2.990000e+02 3.530901e+02 +9 122 -2.700900e+02 2.360400e+02 +10 122 -2.020200e+02 -3.752600e+02 +11 122 3.742000e+02 1.727100e+02 +12 122 -8.177300e+02 -4.825500e+02 +13 122 -1.592010e+03 5.623101e+02 +18 122 -4.404200e+02 3.000000e+01 +20 122 -3.731500e+02 -1.720100e+02 +0 123 7.536899e+02 2.180300e+02 +1 123 -5.792800e+02 2.064099e+02 +2 123 -1.796900e+02 1.473000e+02 +3 123 -6.076500e+02 3.218201e+02 +4 123 1.010480e+03 3.489600e+02 +5 123 6.058900e+02 7.542200e+02 +6 123 -2.379400e+02 1.202500e+02 +7 123 3.438700e+02 3.712000e+02 +9 123 -2.260699e+02 2.627200e+02 +10 123 -1.684800e+02 -3.587500e+02 +11 123 4.128500e+02 1.999200e+02 +12 123 -7.764200e+02 -4.623199e+02 +13 123 -1.441010e+03 6.311500e+02 +18 123 -4.124700e+02 4.648999e+01 +20 123 -3.486899e+02 -1.577200e+02 +0 124 1.528160e+03 2.881200e+02 +1 124 8.858201e+02 3.027200e+02 +2 124 7.001200e+02 1.838800e+02 +3 124 9.332000e+02 4.137700e+02 +7 124 8.785200e+02 4.002100e+02 +8 124 7.694399e+02 3.796400e+02 +17 124 -1.041530e+03 6.079500e+02 +0 125 1.488420e+03 2.775400e+02 +1 125 7.469399e+02 2.663800e+02 +2 125 6.137500e+02 1.855500e+02 +3 125 7.509301e+02 3.713800e+02 +6 125 7.009500e+02 1.481100e+02 +17 125 -1.185810e+03 6.154700e+02 +0 126 1.522970e+03 2.928101e+02 +1 126 8.758799e+02 3.113700e+02 +2 126 6.945800e+02 1.892900e+02 +3 126 9.221100e+02 4.222800e+02 +5 126 1.153990e+03 8.903800e+02 +6 126 7.772400e+02 1.845300e+02 +7 126 8.752400e+02 4.030200e+02 +8 126 7.617200e+02 3.867900e+02 +17 126 -1.050690e+03 6.170801e+02 +0 127 1.529290e+03 2.992400e+02 +1 127 8.861101e+02 3.225500e+02 +2 127 7.009200e+02 1.953700e+02 +3 127 9.326699e+02 4.332200e+02 +7 127 8.788701e+02 4.060601e+02 +8 127 7.701801e+02 3.960800e+02 +17 127 -1.040900e+03 6.254000e+02 +0 128 1.523440e+03 3.057600e+02 +1 128 8.760000e+02 3.354399e+02 +2 128 6.949301e+02 2.018800e+02 +3 128 9.231400e+02 4.464500e+02 +5 128 1.153260e+03 9.002400e+02 +8 128 7.620000e+02 4.065000e+02 +0 129 1.570480e+03 3.158101e+02 +1 129 9.780100e+02 3.565901e+02 +2 129 7.536100e+02 2.068600e+02 +3 129 1.037800e+03 4.677400e+02 +6 129 8.476700e+02 2.170100e+02 +17 129 -9.571900e+02 6.402200e+02 +0 130 4.753601e+02 2.850701e+02 +1 130 -1.088510e+03 4.208700e+02 +2 130 -3.532500e+02 2.105600e+02 +7 130 1.947100e+02 4.061799e+02 +11 130 2.769800e+02 2.301000e+02 +12 130 -9.125000e+02 -4.343900e+02 +0 131 5.178899e+02 2.880901e+02 +1 131 -9.983700e+02 4.171400e+02 +2 131 -3.160100e+02 2.144200e+02 +7 131 2.208600e+02 4.090300e+02 +11 131 3.048199e+02 2.353800e+02 +18 131 -4.894300e+02 7.198999e+01 +0 132 4.954099e+02 2.884700e+02 +1 132 -1.045940e+03 4.241300e+02 +2 132 -3.357800e+02 2.156000e+02 +5 132 3.918300e+02 7.657500e+02 +7 132 2.066300e+02 4.092400e+02 +9 132 -3.623101e+02 3.007000e+02 +10 132 -2.732100e+02 -3.239600e+02 +11 132 2.901801e+02 2.351300e+02 +12 132 -9.007200e+02 -4.307300e+02 +0 133 5.030000e+02 2.906899e+02 +1 133 -1.029290e+03 4.263500e+02 +2 133 -3.290400e+02 2.179300e+02 +5 133 3.973300e+02 7.681799e+02 +7 133 2.116100e+02 4.110701e+02 +9 133 -3.571500e+02 3.024900e+02 +11 133 2.951600e+02 2.369300e+02 +0 134 5.681599e+02 3.604199e+02 +1 134 -8.946100e+02 5.541200e+02 +2 134 -2.794100e+02 3.023100e+02 +3 134 -8.860600e+02 7.097700e+02 +4 134 8.969700e+02 4.189900e+02 +7 134 2.494200e+02 4.629399e+02 +9 134 -3.176200e+02 3.712900e+02 +10 134 -2.387600e+02 -2.760100e+02 +11 134 3.324800e+02 3.031700e+02 +12 134 -8.585200e+02 -3.756801e+02 +18 134 -4.695800e+02 1.145701e+02 +20 134 -3.976600e+02 -9.943005e+01 +0 135 4.451001e+02 3.916899e+02 +1 135 -1.147910e+03 6.573000e+02 +2 135 -3.850200e+02 3.391100e+02 +5 135 3.433600e+02 8.370200e+02 +7 135 1.744600e+02 4.829299e+02 +8 135 -9.031800e+02 5.848600e+02 +9 135 -4.022800e+02 3.933600e+02 +11 135 2.530900e+02 3.239200e+02 +12 135 -9.296700e+02 -3.567600e+02 +18 135 -5.230200e+02 1.299700e+02 +0 136 5.964500e+02 3.993101e+02 +1 136 -8.399900e+02 6.235400e+02 +2 136 -2.595900e+02 3.490700e+02 +4 136 9.144199e+02 4.433500e+02 +5 136 4.584600e+02 8.656700e+02 +6 136 -4.487000e+02 4.161500e+02 +7 136 2.645400e+02 4.923000e+02 +8 136 -6.421400e+02 5.858800e+02 +10 136 -2.260900e+02 -2.501400e+02 +11 136 3.480699e+02 3.398400e+02 +12 136 -8.427100e+02 -3.459600e+02 +18 136 -4.584800e+02 1.380400e+02 +0 137 4.382500e+02 4.182600e+02 +1 137 -1.160810e+03 7.189000e+02 +2 137 -3.880100e+02 3.707000e+02 +5 137 3.353101e+02 8.557900e+02 +8 137 -9.149800e+02 6.291200e+02 +9 137 -4.051500e+02 4.170500e+02 +10 137 -3.028300e+02 -2.405100e+02 +11 137 2.507700e+02 3.467200e+02 +12 137 -9.317800e+02 -3.383101e+02 +0 138 4.419199e+02 4.939099e+02 +1 138 -1.146530e+03 8.778800e+02 +2 138 -3.870000e+02 4.620000e+02 +5 138 3.302800e+02 9.139700e+02 +7 138 1.730100e+02 5.561000e+02 +8 138 -9.041700e+02 7.516400e+02 +11 138 2.510200e+02 4.148500e+02 +12 138 -9.286100e+02 -2.835100e+02 +18 138 -5.231200e+02 1.883401e+02 +20 138 -4.437600e+02 -3.665002e+01 +0 139 7.865901e+02 6.345996e+01 +1 139 -5.327500e+02 -1.036000e+02 +2 139 -1.611100e+02 -3.183002e+01 +4 139 1.029530e+03 2.617600e+02 +11 139 4.289800e+02 6.567999e+01 +12 139 -7.637000e+02 -5.722400e+02 +0 140 7.688999e+02 6.869995e+01 +1 140 -5.577800e+02 -8.393994e+01 +2 140 -1.672800e+02 -2.809998e+01 +3 140 -5.841700e+02 1.689001e+01 +4 140 1.017980e+03 2.609199e+02 +5 140 6.329000e+02 6.417700e+02 +6 140 -2.280200e+02 -8.044000e+01 +7 140 3.519900e+02 2.638700e+02 +9 140 -2.163600e+02 1.287300e+02 +10 140 -1.609900e+02 -4.547000e+02 +11 140 4.232800e+02 6.860999e+01 +12 140 -7.708700e+02 -5.691700e+02 +18 140 -4.067900e+02 -3.875000e+01 +0 141 7.746499e+02 1.013000e+02 +1 141 -5.477300e+02 -2.506995e+01 +2 141 -1.638900e+02 9.049988e+00 +3 141 -5.772200e+02 7.758002e+01 +4 141 1.021890e+03 2.812000e+02 +5 141 6.343101e+02 6.678300e+02 +6 141 -2.172100e+02 -4.046997e+01 +11 141 4.256600e+02 9.720001e+01 +0 142 7.684099e+02 1.065300e+02 +1 142 -5.562500e+02 -1.366998e+01 +2 142 -1.667700e+02 1.652002e+01 +3 142 -5.827700e+02 8.890002e+01 +4 142 1.018130e+03 2.842700e+02 +5 142 6.278400e+02 6.700500e+02 +6 142 -2.256800e+02 -3.192999e+01 +7 142 3.527400e+02 2.919000e+02 +9 142 -2.158500e+02 1.634299e+02 +10 142 -1.604800e+02 -4.304600e+02 +11 142 4.236500e+02 1.027900e+02 +12 142 -7.692700e+02 -5.412800e+02 +18 142 -4.063101e+02 -1.602002e+01 +20 142 -3.436500e+02 -2.116300e+02 +0 143 6.065200e+02 1.531699e+02 +1 143 -8.325100e+02 1.111200e+02 +2 143 -2.564700e+02 5.903003e+01 +5 143 4.915500e+02 6.808300e+02 +7 143 2.690500e+02 3.164500e+02 +9 143 -2.956000e+02 1.868401e+02 +10 143 -2.231801e+02 -4.079900e+02 +12 143 -8.445000e+02 -5.216100e+02 +13 143 -1.689470e+03 4.187600e+02 +18 143 -4.586600e+02 -7.099609e-01 +0 144 1.525070e+03 1.782400e+02 +1 144 8.844800e+02 1.075300e+02 +2 144 6.982100e+02 7.108002e+01 +3 144 9.328000e+02 2.147500e+02 +8 144 7.641100e+02 2.134800e+02 +17 144 -1.044790e+03 4.356899e+02 +0 145 4.974600e+02 1.757400e+02 +1 145 -1.047630e+03 1.802900e+02 +2 145 -3.352800e+02 8.134998e+01 +3 145 -1.026280e+03 3.122700e+02 +6 145 -6.196100e+02 1.197700e+02 +7 145 2.076400e+02 3.286799e+02 +8 145 -8.205200e+02 2.300100e+02 +11 145 2.909000e+02 1.366700e+02 +0 146 6.792900e+02 2.025300e+02 +1 146 -7.061900e+02 1.917600e+02 +2 146 -2.229200e+02 1.200600e+02 +4 146 9.631699e+02 3.353201e+02 +5 146 5.462500e+02 7.301500e+02 +6 146 -3.427300e+02 1.142200e+02 +10 146 -1.978101e+02 -3.729301e+02 +12 146 -8.120500e+02 -4.800699e+02 +18 146 -4.369200e+02 3.170996e+01 +0 147 7.530601e+02 2.278301e+02 +1 147 -5.794700e+02 2.246100e+02 +2 147 -1.792800e+02 1.580700e+02 +3 147 -6.073500e+02 3.389500e+02 +5 147 6.045200e+02 7.616700e+02 +6 147 -2.381200e+02 1.328100e+02 +7 147 3.436300e+02 3.784299e+02 +10 147 -1.683700e+02 -3.529500e+02 +11 147 4.137500e+02 2.083100e+02 +12 147 -7.761900e+02 -4.547300e+02 +13 147 -1.439130e+03 6.578201e+02 +18 147 -4.124500e+02 5.225000e+01 +0 148 6.501399e+02 2.423600e+02 +1 148 -7.518900e+02 2.816899e+02 +2 148 -2.355900e+02 1.697500e+02 +4 148 9.453999e+02 3.568800e+02 +5 148 5.181500e+02 7.551400e+02 +7 148 2.905699e+02 3.826699e+02 +10 148 -2.075500e+02 -3.482200e+02 +11 148 3.682300e+02 2.094900e+02 +12 148 -8.238900e+02 -4.535400e+02 +13 148 -1.614400e+03 6.875300e+02 +0 149 6.033601e+02 2.624900e+02 +1 149 -8.339800e+02 3.389000e+02 +2 149 -2.582100e+02 1.887900e+02 +3 149 -8.261100e+02 4.735701e+02 +4 149 9.166201e+02 3.654299e+02 +5 149 4.774700e+02 7.627800e+02 +7 149 2.672800e+02 3.947100e+02 +9 149 -2.992100e+02 2.865000e+02 +10 149 -2.243000e+02 -3.373000e+02 +11 149 3.494000e+02 2.212400e+02 +12 149 -8.440400e+02 -4.429100e+02 +13 149 -1.691000e+03 7.421700e+02 +0 150 1.592100e+03 3.053700e+02 +1 150 1.018260e+03 3.363500e+02 +2 150 7.759000e+02 1.954600e+02 +3 150 1.081080e+03 4.488300e+02 +5 150 1.195580e+03 9.039399e+02 +6 150 8.779200e+02 2.042400e+02 +8 150 8.549900e+02 4.058800e+02 +12 150 -2.086400e+02 -4.433500e+02 +17 150 -9.228900e+02 6.211599e+02 +0 151 7.705701e+02 2.610000e+02 +1 151 -5.487300e+02 2.865000e+02 +2 151 -1.651600e+02 1.981900e+02 +3 151 -5.792600e+02 4.028101e+02 +4 151 1.021290e+03 3.751100e+02 +6 151 -2.123400e+02 1.744600e+02 +10 151 -1.598900e+02 -3.303199e+02 +11 151 4.247300e+02 2.393500e+02 +12 151 -7.651800e+02 -4.296899e+02 +0 152 5.520901e+02 2.844199e+02 +1 152 -9.289500e+02 4.008700e+02 +2 152 -2.884400e+02 2.111600e+02 +3 152 -9.132300e+02 5.450701e+02 +4 152 8.864399e+02 3.749399e+02 +5 152 4.352000e+02 7.707000e+02 +7 152 2.406600e+02 4.075601e+02 +8 152 -7.239300e+02 4.033201e+02 +9 152 -3.244600e+02 2.997100e+02 +10 152 -2.447100e+02 -3.257900e+02 +11 152 3.257300e+02 2.342500e+02 +12 152 -8.680100e+02 -4.317700e+02 +18 152 -4.749399e+02 7.065002e+01 +0 153 5.391499e+02 2.849000e+02 +1 153 -9.548100e+02 4.060601e+02 +2 153 -2.982400e+02 2.120700e+02 +3 153 -9.379800e+02 5.516200e+02 +4 153 8.788201e+02 3.749600e+02 +5 153 4.252300e+02 7.694600e+02 +6 153 -5.449800e+02 2.700600e+02 +7 153 2.331700e+02 4.077300e+02 +8 153 -7.465600e+02 4.054000e+02 +9 153 -3.324000e+02 2.998401e+02 +10 153 -2.509500e+02 -3.254399e+02 +11 153 3.182300e+02 2.345400e+02 +12 153 -8.750600e+02 -4.316899e+02 +0 154 5.100801e+02 2.860901e+02 +1 154 -1.015130e+03 4.155901e+02 +2 154 -3.226900e+02 2.139200e+02 +4 154 8.616699e+02 3.741799e+02 +8 154 -7.965100e+02 4.092500e+02 +9 154 -3.520699e+02 2.988700e+02 +11 154 2.996400e+02 2.343400e+02 +0 155 5.326299e+02 2.881200e+02 +1 155 -9.683800e+02 4.144600e+02 +2 155 -3.037900e+02 2.151200e+02 +7 155 2.293900e+02 4.097200e+02 +8 155 -7.574000e+02 4.110100e+02 +9 155 -3.370000e+02 3.019099e+02 +11 155 3.141200e+02 2.362200e+02 +0 156 4.773701e+02 3.158500e+02 +1 156 -1.080370e+03 4.903900e+02 +2 156 -3.441400e+02 2.460500e+02 +3 156 -1.060210e+03 6.488000e+02 +7 156 1.981400e+02 4.275601e+02 +8 156 -8.556700e+02 4.599299e+02 +9 156 -3.700699e+02 3.226899e+02 +10 156 -2.787900e+02 -3.072400e+02 +11 156 2.837800e+02 2.563600e+02 +12 156 -9.072600e+02 -4.127700e+02 +0 157 4.630300e+02 3.857700e+02 +1 157 -1.108760e+03 6.398101e+02 +2 157 -3.669100e+02 3.318300e+02 +4 157 8.353701e+02 4.292500e+02 +5 157 3.575699e+02 8.350300e+02 +6 157 -6.525200e+02 4.336000e+02 +7 157 1.868400e+02 4.788301e+02 +8 157 -8.723800e+02 5.742900e+02 +9 157 -3.877500e+02 3.885901e+02 +11 157 2.667400e+02 3.192200e+02 +0 158 1.607150e+03 8.577002e+01 +1 158 1.054960e+03 -5.889001e+01 +2 158 7.932500e+02 -2.984998e+01 +5 158 1.218850e+03 7.387000e+02 +6 158 8.930000e+02 -8.873999e+01 +7 158 9.278899e+02 2.627300e+02 +12 158 -2.012100e+02 -5.799100e+02 +17 158 -8.975100e+02 2.801500e+02 +0 159 7.746499e+02 1.013000e+02 +1 159 -5.477300e+02 -2.506995e+01 +2 159 -1.644200e+02 9.169983e+00 +3 159 -5.772200e+02 7.758002e+01 +4 159 1.021890e+03 2.812000e+02 +5 159 6.343101e+02 6.678300e+02 +6 159 -2.172100e+02 -4.046997e+01 +0 160 1.493470e+03 1.144100e+02 +1 160 7.588401e+02 -2.135999e+01 +2 160 6.197300e+02 1.231000e+01 +3 160 7.635800e+02 7.950000e+01 +6 160 7.042000e+02 -5.984003e+01 +12 160 -2.834500e+02 -5.486100e+02 +17 160 -1.177740e+03 3.491400e+02 +0 161 6.001299e+02 1.398700e+02 +1 161 -8.473000e+02 8.688000e+01 +2 161 -2.610400e+02 4.663000e+01 +4 161 9.142800e+02 2.956799e+02 +5 161 4.880300e+02 6.702600e+02 +7 161 2.646300e+02 3.082700e+02 +9 161 -2.997900e+02 1.761400e+02 +10 161 -2.258700e+02 -4.157000e+02 +11 161 3.476700e+02 1.162200e+02 +13 161 -1.704060e+03 3.878500e+02 +0 162 5.736799e+02 1.644299e+02 +1 162 -8.936200e+02 1.431400e+02 +2 162 -2.731700e+02 7.081000e+01 +0 163 1.588890e+03 1.917000e+02 +1 163 1.019200e+03 1.331799e+02 +2 163 7.739900e+02 7.877002e+01 +3 163 1.082020e+03 2.413600e+02 +6 163 8.724800e+02 5.454999e+01 +7 163 9.169900e+02 3.321799e+02 +8 163 8.506600e+02 2.334100e+02 +12 163 -2.118500e+02 -5.139900e+02 +17 163 -9.259600e+02 4.447000e+02 +0 164 5.878501e+02 1.820200e+02 +1 164 -8.661300e+02 1.760000e+02 +2 164 -2.668300e+02 9.177002e+01 +3 164 -8.528600e+02 3.005300e+02 +4 164 9.065300e+02 3.185901e+02 +6 164 -4.803800e+02 1.108400e+02 +7 164 2.589800e+02 3.360601e+02 +10 164 -2.302100e+02 -3.901000e+02 +11 164 3.433800e+02 1.485100e+02 +12 164 -8.527900e+02 -5.024399e+02 +0 165 5.816699e+02 2.281699e+02 +1 165 -8.764400e+02 2.736699e+02 +2 165 -2.720700e+02 1.468000e+02 +4 165 9.032500e+02 3.448101e+02 +7 165 2.555000e+02 3.689900e+02 +9 165 -3.100601e+02 2.524299e+02 +11 165 3.387300e+02 1.887500e+02 +0 166 7.680000e+02 2.514700e+02 +1 166 -5.540600e+02 2.668201e+02 +2 166 -1.688200e+02 1.871800e+02 +4 166 1.020370e+03 3.694500e+02 +5 166 6.141801e+02 7.822500e+02 +7 166 3.520100e+02 3.963900e+02 +9 166 -2.187700e+02 2.964600e+02 +10 166 -1.621500e+02 -3.367100e+02 +13 166 -1.407890e+03 7.300601e+02 +18 166 -4.057900e+02 6.657007e+01 +0 167 4.700601e+02 2.763201e+02 +1 167 -1.100730e+03 4.045400e+02 +2 167 -3.574000e+02 2.002100e+02 +7 167 1.915601e+02 4.001300e+02 +11 167 2.741100e+02 2.226500e+02 +0 168 5.455701e+02 2.856500e+02 +1 168 -9.424500e+02 4.051799e+02 +2 168 -2.935800e+02 2.105800e+02 +3 168 -9.256000e+02 5.504900e+02 +4 168 8.825200e+02 3.752700e+02 +5 168 4.301500e+02 7.710100e+02 +6 168 -5.358700e+02 2.698300e+02 +7 168 2.369399e+02 4.083700e+02 +9 168 -3.286700e+02 2.986000e+02 +10 168 -2.477700e+02 -3.253101e+02 +11 168 3.219700e+02 2.335800e+02 +0 169 1.587370e+03 3.341000e+02 +1 169 1.010500e+03 3.887300e+02 +2 169 7.721200e+02 2.251600e+02 +3 169 1.072940e+03 5.028800e+02 +8 169 8.485500e+02 4.498900e+02 +12 169 -2.107400e+02 -4.256200e+02 +17 169 -9.292400e+02 6.669399e+02 +0 170 1.100680e+03 3.121599e+02 +1 170 -2.076801e+02 2.384299e+02 +5 170 9.518000e+02 9.189500e+02 +8 170 2.477800e+02 3.874299e+02 +0 171 4.597900e+02 4.120901e+02 +1 171 -1.112420e+03 6.992600e+02 +2 171 -3.659200e+02 3.613100e+02 +7 171 1.859500e+02 4.967200e+02 +8 171 -8.789200e+02 6.173900e+02 +9 171 -3.875800e+02 4.113000e+02 +0 172 1.583890e+03 4.318301e+02 +1 172 7.056201e+02 4.580500e+02 +2 172 5.659500e+02 3.870400e+02 +3 172 6.017600e+02 5.483400e+02 +6 172 7.342600e+02 2.737700e+02 +17 172 -1.300980e+03 9.344199e+02 +0 173 1.583890e+03 4.318301e+02 +1 173 7.056201e+02 4.580500e+02 +2 173 5.659500e+02 3.870400e+02 +3 173 6.017600e+02 5.483400e+02 +6 173 7.342600e+02 2.737700e+02 +7 173 8.809099e+02 5.351200e+02 +17 173 -1.300980e+03 9.344199e+02 +0 174 1.658890e+03 4.534199e+02 +1 174 8.158201e+02 4.859399e+02 +2 174 6.398300e+02 4.050800e+02 +3 174 7.094100e+02 5.736899e+02 +6 174 8.163800e+02 2.933100e+02 +0 175 5.136201e+02 4.822900e+02 +1 175 -9.965400e+02 8.294900e+02 +2 175 -3.205500e+02 4.470300e+02 +8 175 -7.830700e+02 7.271300e+02 +9 175 -3.525699e+02 4.794399e+02 +10 175 -2.631700e+02 -1.987100e+02 +12 175 -8.849200e+02 -2.910100e+02 +0 176 7.609199e+02 5.943005e+01 +1 176 -5.709000e+02 -1.048300e+02 +2 176 -1.715600e+02 -4.350000e+01 +9 176 -2.195699e+02 1.161500e+02 +0 177 7.546299e+02 6.768994e+01 +1 177 -5.804100e+02 -8.881995e+01 +2 177 -1.750200e+02 -3.308002e+01 +3 177 -6.033000e+02 1.078998e+01 +4 177 1.008660e+03 2.609099e+02 +6 177 -2.468900e+02 -8.263000e+01 +7 177 3.444900e+02 2.618900e+02 +11 177 4.170300e+02 6.475000e+01 +0 178 1.559700e+03 8.168994e+01 +1 178 9.638401e+02 -6.651001e+01 +2 178 7.417900e+02 -3.209998e+01 +3 178 1.022960e+03 3.794000e+01 +5 178 1.188540e+03 7.320800e+02 +8 178 8.112500e+02 6.594000e+01 +17 178 -9.747500e+02 2.777400e+02 +0 179 7.613000e+02 1.090601e+02 +1 179 -5.691900e+02 -8.429993e+00 +2 179 -1.716400e+02 1.632001e+01 +3 179 -5.947800e+02 9.750000e+01 +4 179 1.013560e+03 2.861400e+02 +5 179 6.225900e+02 6.719100e+02 +7 179 3.479900e+02 2.926899e+02 +9 179 -2.202600e+02 1.633000e+02 +18 179 -4.092200e+02 -1.612000e+01 +0 180 7.684800e+02 2.375901e+02 +1 180 -5.542300e+02 2.386699e+02 +2 180 -1.687100e+02 1.667400e+02 +4 180 1.020310e+03 3.613301e+02 +5 180 6.162900e+02 7.725500e+02 +6 180 -2.171500e+02 1.426400e+02 +11 180 4.222500e+02 2.149100e+02 +13 180 -1.407520e+03 6.790000e+02 +0 181 1.490480e+03 2.614900e+02 +1 181 7.504099e+02 2.385400e+02 +2 181 6.158800e+02 1.692100e+02 +3 181 7.541200e+02 3.440500e+02 +6 181 7.038800e+02 1.283000e+02 +17 181 -1.183920e+03 5.902200e+02 +0 182 4.448701e+02 4.084600e+02 +1 182 -1.145020e+03 6.949399e+02 +2 182 -3.812500e+02 3.585300e+02 +9 182 -3.991400e+02 4.081300e+02 +0 183 5.007400e+02 4.275901e+02 +1 183 -1.026000e+03 7.165601e+02 +2 183 -3.335300e+02 3.813500e+02 +5 183 3.816400e+02 8.703700e+02 +8 183 -8.068300e+02 6.384700e+02 +11 183 2.915800e+02 3.578101e+02 +0 184 1.571590e+03 1.085400e+02 +1 184 9.888701e+02 -1.690002e+01 +3 184 1.048660e+03 8.791998e+01 +8 184 8.274000e+02 1.070700e+02 +12 184 -2.222300e+02 -5.648000e+02 +0 185 5.655601e+02 2.710701e+02 +1 185 -9.048800e+02 3.687900e+02 +2 185 -2.805500e+02 1.963700e+02 +0 186 1.656930e+03 2.540000e+02 +1 186 1.136470e+03 2.438800e+02 +5 186 1.244310e+03 8.716801e+02 +6 186 9.649399e+02 1.366100e+02 +7 186 9.586899e+02 3.709800e+02 +8 186 9.428199e+02 3.275100e+02 +12 186 -1.736000e+02 -4.784000e+02 +0 187 1.682980e+03 2.078800e+02 +1 187 1.184940e+03 1.604099e+02 +7 187 9.753601e+02 3.402600e+02 +8 187 9.796000e+02 2.564399e+02 +12 187 -1.583900e+02 -5.076400e+02 +17 187 -7.867300e+02 4.594299e+02 +18 187 8.284998e+01 8.040039e+00 +20 187 7.767004e+01 -1.879399e+02 +0 188 7.157400e+02 2.460200e+02 +1 188 -6.397300e+02 2.719700e+02 +4 188 9.866201e+02 3.627600e+02 +5 188 5.716899e+02 7.694399e+02 +6 188 -2.897800e+02 1.684200e+02 +9 188 -2.396400e+02 2.833301e+02 +11 188 4.035000e+02 2.187700e+02 +18 188 -4.196200e+02 5.910999e+01 +20 188 -3.549200e+02 -1.469800e+02 +0 189 7.324900e+02 1.149600e+02 +1 189 -6.185400e+02 7.450012e+00 +3 189 -6.382800e+02 1.114500e+02 +4 189 9.954600e+02 2.878000e+02 +5 189 5.985000e+02 6.720200e+02 +7 189 3.317500e+02 2.947700e+02 +0 190 6.642500e+02 1.669299e+02 +1 190 -7.301900e+02 1.254800e+02 +6 190 -3.670900e+02 7.058002e+01 +0 191 6.528201e+02 2.266200e+02 +1 191 -7.473800e+02 2.506000e+02 +3 191 -7.501900e+02 3.751899e+02 +4 191 9.465701e+02 3.480500e+02 +5 191 5.215800e+02 7.437300e+02 +6 191 -3.776200e+02 1.561900e+02 +7 191 2.912700e+02 3.731100e+02 +10 191 -2.067700e+02 -3.570200e+02 +12 191 -8.232200e+02 -4.636400e+02 +13 191 -1.612140e+03 6.487100e+02 +18 191 -4.440699e+02 4.591003e+01 +20 191 -3.760900e+02 -1.584900e+02 +0 192 6.116699e+02 1.846000e+02 +1 192 -8.238400e+02 1.755300e+02 +4 192 9.213501e+02 3.213800e+02 +5 192 4.928500e+02 7.056799e+02 +7 192 2.715699e+02 3.384199e+02 +12 192 -8.416300e+02 -4.994900e+02 +13 192 -1.679030e+03 5.089900e+02 +0 193 6.434299e+02 1.979800e+02 +1 193 -7.665400e+02 1.928000e+02 +4 193 9.406799e+02 3.309299e+02 +5 193 5.172000e+02 7.211300e+02 +6 193 -3.944100e+02 1.183400e+02 +0 194 6.897500e+02 2.133201e+02 +1 194 -6.874500e+02 2.124600e+02 +4 194 9.697000e+02 3.427500e+02 +5 194 5.540699e+02 7.400601e+02 +0 195 8.289500e+02 2.023301e+02 +1 195 -4.699500e+02 1.535000e+02 +3 195 -5.240400e+02 2.580601e+02 +4 195 1.060690e+03 3.459500e+02 +5 195 6.731700e+02 7.571300e+02 +7 195 3.793500e+02 3.649800e+02 +9 195 -1.983101e+02 2.594099e+02 +10 195 -1.451899e+02 -3.651400e+02 +11 195 4.389200e+02 1.959600e+02 +13 195 -1.336080e+03 5.956200e+02 +18 195 -3.930300e+02 4.389001e+01 +0 196 8.543899e+02 1.603201e+02 +1 196 -4.321000e+02 7.002002e+01 +4 196 1.076260e+03 3.208800e+02 +5 196 6.989200e+02 7.272100e+02 +6 196 -1.120900e+02 1.969000e+01 +7 196 3.940300e+02 3.367600e+02 +0 197 7.865901e+02 6.345996e+01 +1 197 -5.327500e+02 -1.036000e+02 +4 197 1.029530e+03 2.617600e+02 +0 198 6.378501e+02 2.784600e+02 +1 198 -7.703200e+02 3.634600e+02 +3 198 -7.712200e+02 4.969399e+02 +4 198 9.384299e+02 3.760701e+02 +5 198 5.047100e+02 7.804200e+02 +6 198 -3.934000e+02 2.323600e+02 +7 198 2.853800e+02 4.081300e+02 +10 198 -2.112100e+02 -3.254700e+02 +13 198 -1.629540e+03 7.952200e+02 +0 199 8.013799e+02 1.125200e+02 +1 199 -5.086700e+02 -5.919983e+00 +4 199 1.040920e+03 2.886699e+02 +5 199 6.564500e+02 6.809600e+02 +6 199 -1.829900e+02 -2.906000e+01 +10 199 -1.503700e+02 -4.242000e+02 +12 199 -7.566400e+02 -5.325900e+02 +18 199 -3.976899e+02 -1.022998e+01 +0 200 8.545400e+02 1.137700e+02 +1 200 -4.351600e+02 -1.715002e+01 +4 200 1.076430e+03 2.938700e+02 +5 200 7.044301e+02 6.917900e+02 +6 200 -1.136300e+02 -3.945001e+01 +0 201 8.018899e+02 1.796300e+02 +1 201 -5.066400e+02 1.203500e+02 +4 201 1.041860e+03 3.299800e+02 +5 201 6.508700e+02 7.332800e+02 +0 202 7.689600e+02 8.747998e+01 +1 202 -5.579400e+02 -5.302002e+01 +4 202 1.018290e+03 2.727600e+02 +5 202 6.310500e+02 6.567600e+02 +6 202 -2.264300e+02 -5.756000e+01 +0 203 8.611899e+02 1.255300e+02 +1 203 -4.264000e+02 4.229980e+00 +4 203 1.081650e+03 3.013700e+02 +5 203 7.094500e+02 7.018300e+02 +8 203 -1.815700e+02 1.311000e+02 +10 203 -1.343800e+02 -4.135601e+02 +0 204 5.812800e+02 1.690000e+02 +1 204 -8.816700e+02 1.507000e+02 +4 204 9.031101e+02 3.109199e+02 +0 205 4.895300e+02 4.534099e+02 +1 205 -1.047840e+03 7.791200e+02 +4 205 8.516101e+02 4.706500e+02 +5 205 3.700900e+02 8.935400e+02 +8 205 -8.244100e+02 6.849900e+02 +0 206 5.536799e+02 3.944000e+02 +1 206 -9.208300e+02 6.336799e+02 +4 206 8.889099e+02 4.376699e+02 +5 206 4.249200e+02 8.547400e+02 +8 206 -7.183300e+02 5.837400e+02 +11 206 3.270300e+02 3.330400e+02 +0 207 5.742900e+02 3.135300e+02 +1 207 -8.817600e+02 4.566599e+02 +4 207 9.001399e+02 3.917300e+02 +5 207 4.488199e+02 7.963400e+02 +8 207 -6.854300e+02 4.504900e+02 +0 208 4.315400e+02 4.947000e+02 +1 208 -1.169380e+03 8.843900e+02 +4 208 8.186899e+02 4.898700e+02 +5 208 3.225100e+02 9.127800e+02 +6 208 -6.904800e+02 6.014900e+02 +7 208 1.674600e+02 5.574600e+02 +8 208 -9.220200e+02 7.539800e+02 +9 208 -4.103700e+02 4.875000e+02 +12 208 -9.347900e+02 -2.825699e+02 +0 209 4.952000e+02 4.530701e+02 +1 209 -1.037010e+03 7.722700e+02 +8 209 -8.136400e+02 6.811899e+02 +0 210 5.576899e+02 4.327700e+02 +1 210 -9.107000e+02 7.078800e+02 +4 210 8.913501e+02 4.600701e+02 +5 210 4.238101e+02 8.842200e+02 +7 210 2.437000e+02 5.151100e+02 +8 210 -7.074800e+02 6.434600e+02 +0 211 5.294399e+02 4.420801e+02 +1 211 -9.680600e+02 7.383700e+02 +4 211 8.747700e+02 4.643000e+02 +5 211 4.022500e+02 8.875400e+02 +6 211 -5.442200e+02 4.973300e+02 +8 211 -7.557000e+02 6.607400e+02 +0 212 5.672300e+02 3.504500e+02 +1 212 -8.956800e+02 5.344800e+02 +4 212 8.961201e+02 4.133700e+02 +5 212 4.404200e+02 8.234399e+02 +7 212 2.489200e+02 4.560000e+02 +8 212 -6.948000e+02 5.096500e+02 +9 212 -3.167300e+02 3.619099e+02 +0 213 7.542700e+02 5.960999e+01 +1 213 -5.815100e+02 -1.042000e+02 +3 213 -6.038100e+02 -4.739990e+00 +4 213 1.008430e+03 2.560901e+02 +5 213 6.213400e+02 6.329600e+02 +6 213 -2.483800e+02 -9.289001e+01 +7 213 3.444000e+02 2.558600e+02 +0 214 7.608501e+02 1.535500e+02 +1 214 -5.688100e+02 7.815002e+01 +3 214 -5.960600e+02 1.854399e+02 +4 214 1.013900e+03 3.110601e+02 +5 214 6.179399e+02 7.061600e+02 +6 214 -2.329400e+02 3.178003e+01 +11 214 4.187400e+02 1.420400e+02 +0 215 8.954500e+02 2.116200e+02 +1 215 -3.781000e+02 1.529399e+02 +3 215 -4.543400e+02 2.532200e+02 +4 215 1.107330e+03 3.567500e+02 +5 215 7.320300e+02 7.759100e+02 +7 215 4.120200e+02 3.773700e+02 +8 215 -1.220600e+02 2.618201e+02 +9 215 -1.721200e+02 2.804199e+02 +10 215 -1.237400e+02 -3.539399e+02 +11 215 4.614600e+02 2.156400e+02 +12 215 -7.179000e+02 -4.499800e+02 +13 215 -1.238460e+03 6.372600e+02 +18 215 -3.748199e+02 5.657007e+01 +0 216 7.669500e+02 4.380005e+01 +1 216 -5.613300e+02 -1.363500e+02 +4 216 1.016370e+03 2.476599e+02 +6 216 -2.320900e+02 -1.158600e+02 +11 216 4.230699e+02 4.590997e+01 +0 217 7.481101e+02 2.240801e+02 +1 217 -5.897500e+02 2.196899e+02 +5 217 6.011899e+02 7.581100e+02 +6 217 -2.447600e+02 1.284200e+02 +7 217 3.387800e+02 3.763101e+02 +10 217 -1.724399e+02 -3.547100e+02 +12 217 -7.807300e+02 -4.576300e+02 +13 217 -1.459380e+03 6.510400e+02 +0 218 8.900801e+02 1.291300e+02 +1 218 -3.868101e+02 4.880005e+00 +4 218 1.102040e+03 3.052500e+02 +5 218 7.356100e+02 7.101300e+02 +8 218 -1.323000e+02 1.357700e+02 +0 219 5.186699e+02 3.547300e+02 +1 219 -9.949000e+02 5.588101e+02 +4 219 8.665300e+02 4.129900e+02 +5 219 4.027300e+02 8.219700e+02 +8 219 -7.769100e+02 5.195400e+02 +0 220 5.497900e+02 1.684199e+02 +1 220 -9.386800e+02 1.570100e+02 +6 220 -5.392800e+02 1.003000e+02 +0 221 1.609930e+03 1.169399e+02 +1 221 1.058460e+03 -3.020020e+00 +5 221 1.219480e+03 7.627500e+02 +6 221 8.989600e+02 -4.639001e+01 +7 221 9.294500e+02 2.832200e+02 +17 221 -8.942700e+02 3.270200e+02 +0 222 1.692290e+03 1.983401e+02 +1 222 1.199500e+03 1.429600e+02 +7 222 9.803301e+02 3.339600e+02 +8 222 9.922700e+02 2.423200e+02 +9 222 5.806299e+02 2.121100e+02 +12 222 -1.536000e+02 -5.134700e+02 +17 222 -7.753000e+02 4.448401e+02 +0 223 6.392400e+02 8.867004e+01 +1 223 -7.767200e+02 -2.835999e+01 +3 223 -7.707500e+02 7.897998e+01 +4 223 9.369399e+02 2.681200e+02 +7 223 2.854700e+02 2.719900e+02 +11 223 3.665000e+02 6.975000e+01 +18 223 -4.480900e+02 -3.627002e+01 +20 223 -3.795300e+02 -2.292000e+02 +0 224 7.853201e+02 1.255699e+02 +1 224 -5.294100e+02 2.082001e+01 +3 224 -5.622200e+02 1.225100e+02 +6 224 -2.026400e+02 -9.200012e+00 +0 225 7.961001e+02 3.990002e+01 +1 225 -5.173100e+02 -1.474700e+02 +3 225 -5.538400e+02 -5.115002e+01 +6 225 -1.924500e+02 -1.257100e+02 +0 226 9.045500e+02 8.013000e+01 +1 226 -3.664301e+02 -8.762000e+01 +3 226 -4.408600e+02 6.169983e+00 +5 226 7.513500e+02 6.733500e+02 +8 226 -1.099100e+02 5.821002e+01 +11 226 4.678400e+02 9.485999e+01 +13 226 -1.223440e+03 2.424000e+02 +0 227 5.974099e+02 2.622700e+02 +1 227 -8.448700e+02 3.394600e+02 +3 227 -8.367600e+02 4.749700e+02 +0 228 1.156710e+03 1.903900e+02 +1 228 -1.133700e+02 4.403003e+01 +3 228 -3.051300e+02 1.239100e+02 +11 228 4.990100e+02 2.606600e+02 +13 228 -1.000650e+03 6.648500e+02 +0 229 8.275601e+02 1.642300e+02 +1 229 -4.728199e+02 8.383008e+01 +5 229 6.759399e+02 7.251899e+02 +13 229 -1.337930e+03 4.859700e+02 +0 230 1.691700e+03 2.482000e+02 +1 230 1.198640e+03 2.322500e+02 +8 230 9.921500e+02 3.179299e+02 +12 230 -1.530200e+02 -4.833000e+02 +17 230 -7.740200e+02 5.202600e+02 +0 231 1.326460e+03 1.669500e+02 +1 231 -4.683997e+01 -4.495996e+01 +6 231 3.205500e+02 -8.839001e+01 +8 231 6.088000e+02 1.547900e+02 +12 231 -6.163000e+02 -3.622800e+02 +16 231 7.979500e+02 4.080400e+02 +0 232 4.753101e+02 3.873401e+02 +1 232 -1.082130e+03 6.400601e+02 +3 232 -1.069700e+03 8.110800e+02 +7 232 1.947300e+02 4.798900e+02 +9 232 -3.782800e+02 3.905200e+02 +10 232 -2.834100e+02 -2.603500e+02 +12 232 -9.099000e+02 -3.601200e+02 +0 233 1.594090e+03 1.466300e+02 +1 233 1.028050e+03 5.116992e+01 +3 233 1.090810e+03 1.577800e+02 +8 233 8.581801e+02 1.648900e+02 +12 233 -2.087700e+02 -5.419399e+02 +17 233 -9.190300e+02 3.747600e+02 +0 234 5.455701e+02 2.856500e+02 +1 234 -9.424500e+02 4.051799e+02 +4 234 8.825200e+02 3.752700e+02 +7 234 2.369399e+02 4.083700e+02 +10 234 -2.477700e+02 -3.253101e+02 +12 234 -8.714200e+02 -4.304600e+02 +0 235 1.629940e+03 3.386100e+02 +1 235 1.085490e+03 3.948700e+02 +7 235 9.447000e+02 4.272400e+02 +12 235 -1.868900e+02 -4.252800e+02 +0 236 6.971799e+02 2.229399e+02 +1 236 -6.726000e+02 2.301799e+02 +4 236 9.745300e+02 3.485200e+02 +6 236 -3.164800e+02 1.394600e+02 +13 236 -1.531610e+03 6.416400e+02 +0 237 4.536499e+02 3.907500e+02 +1 237 -1.128680e+03 6.528400e+02 +4 237 8.302600e+02 4.320000e+02 +7 237 1.804800e+02 4.822300e+02 +18 237 -5.186300e+02 1.291899e+02 +0 238 5.886299e+02 2.453201e+02 +1 238 -8.610300e+02 3.078900e+02 +0 239 1.603150e+03 2.952400e+02 +1 239 8.864900e+02 2.872900e+02 +0 240 9.631499e+02 1.348900e+02 +1 240 -2.951899e+02 -2.679993e+00 +3 240 -3.943800e+02 8.756000e+01 +4 240 1.156180e+03 3.154099e+02 +8 240 -7.390015e+00 1.397300e+02 +16 240 6.208900e+02 3.395900e+02 +0 241 8.018999e+02 8.020020e+00 +1 241 -5.099100e+02 -2.086700e+02 +3 241 -5.458700e+02 -1.142300e+02 +4 241 1.039120e+03 2.279700e+02 +6 241 -1.881800e+02 -1.692600e+02 +0 242 8.015300e+02 4.734998e+01 +1 242 -5.101900e+02 -1.351700e+02 +3 242 -5.464000e+02 -3.992999e+01 +4 242 1.039820e+03 2.498401e+02 +5 242 6.637600e+02 6.312100e+02 +0 243 7.086101e+02 1.938000e+02 +1 243 -6.570400e+02 1.665400e+02 +4 243 9.816799e+02 3.327900e+02 +5 243 5.717700e+02 7.297600e+02 +0 244 6.485801e+02 2.812100e+02 +1 244 -7.505500e+02 3.645701e+02 +4 244 9.447100e+02 3.783700e+02 +5 244 5.127200e+02 7.838600e+02 +0 245 7.052900e+02 2.101500e+02 +1 245 -6.621500e+02 2.008201e+02 +4 245 9.799800e+02 3.417700e+02 +5 245 5.671000e+02 7.407500e+02 +6 245 -3.049300e+02 1.189900e+02 +7 245 3.170500e+02 3.634299e+02 +10 245 -1.890200e+02 -3.662300e+02 +13 245 -1.531260e+03 5.969900e+02 +18 245 -4.295400e+02 3.905005e+01 +20 245 -3.635800e+02 -1.641700e+02 +0 246 1.683890e+03 2.414900e+02 +1 246 1.186800e+03 2.215100e+02 +7 246 9.754900e+02 3.618500e+02 +8 246 9.820900e+02 3.084100e+02 +17 246 -7.854200e+02 5.107000e+02 +20 246 7.870996e+01 -1.742200e+02 +0 247 8.291299e+02 2.858800e+02 +1 247 -4.681899e+02 3.104299e+02 +4 247 1.062740e+03 3.962400e+02 +5 247 6.658600e+02 8.218400e+02 +8 247 -2.336800e+02 3.830000e+02 +0 248 7.607700e+02 4.558997e+01 +1 248 -5.712500e+02 -1.311000e+02 +4 248 1.012360e+03 2.480200e+02 +5 248 6.284500e+02 6.228101e+02 +6 248 -2.406100e+02 -1.124400e+02 +7 248 3.477100e+02 2.465300e+02 +0 249 7.166899e+02 5.582996e+01 +1 249 -6.450700e+02 -1.072100e+02 +3 249 -6.572400e+02 -7.080017e+00 +4 249 9.847600e+02 2.525100e+02 +0 250 7.741499e+02 1.076801e+02 +1 250 -5.489400e+02 -1.371997e+01 +0 251 6.445000e+02 1.753900e+02 +1 251 -7.655900e+02 1.476599e+02 +4 251 9.408799e+02 3.178500e+02 +5 251 5.199600e+02 7.038700e+02 +7 251 2.870500e+02 3.346200e+02 +0 252 1.676800e+03 2.470500e+02 +1 252 1.172480e+03 2.307800e+02 +8 252 9.703900e+02 3.169399e+02 +10 252 3.919600e+02 -3.609500e+02 +17 252 -7.969900e+02 5.204900e+02 +20 252 7.503003e+01 -1.712600e+02 +0 253 8.379299e+02 2.749299e+02 +1 253 -4.531400e+02 2.886699e+02 +5 253 6.745100e+02 8.139800e+02 +6 253 -1.245600e+02 1.704000e+02 +8 253 -2.206500e+02 3.647100e+02 +0 254 6.100801e+02 7.283997e+01 +1 254 -8.290100e+02 -5.667004e+01 +0 255 7.152300e+02 1.196300e+02 +1 255 -6.489300e+02 1.706000e+01 +3 255 -6.660300e+02 1.230300e+02 +5 255 5.840800e+02 6.727500e+02 +0 256 7.616001e+02 9.125000e+01 +1 256 -5.686100e+02 -4.403003e+01 +3 256 -5.930700e+02 5.715002e+01 +4 256 1.013520e+03 2.751200e+02 +5 256 6.245200e+02 6.583900e+02 +6 256 -2.363100e+02 -5.200000e+01 +0 257 4.996001e+02 4.393500e+02 +1 257 -1.029180e+03 7.426400e+02 +5 257 3.794600e+02 8.810601e+02 +8 257 -8.095400e+02 6.577700e+02 +0 258 5.021399e+02 1.909099e+02 +1 258 -1.037690e+03 2.137100e+02 +8 258 -8.132100e+02 2.548800e+02 +0 259 4.634500e+02 4.394900e+02 +1 259 -1.104220e+03 7.544500e+02 +5 259 3.524200e+02 8.756000e+02 +8 259 -8.694100e+02 6.611899e+02 +0 260 4.703799e+02 3.901799e+02 +1 260 -1.092150e+03 6.492000e+02 +6 260 -6.408700e+02 4.395000e+02 +0 261 4.734199e+02 4.596400e+02 +1 261 -1.081120e+03 7.940400e+02 +0 262 4.883401e+02 4.292800e+02 +1 262 -1.051940e+03 7.240701e+02 +8 262 -8.269200e+02 6.430601e+02 +0 263 5.058401e+02 4.833401e+02 +1 263 -1.011150e+03 8.340701e+02 +8 263 -7.952700e+02 7.299600e+02 +0 264 4.960000e+02 4.311200e+02 +1 264 -1.037170e+03 7.242500e+02 +8 264 -8.144400e+02 6.446000e+02 +0 265 6.205200e+02 2.273101e+02 +1 265 -8.050300e+02 2.642500e+02 +4 265 9.269600e+02 3.456200e+02 +5 265 4.959600e+02 7.391200e+02 +0 266 6.778501e+02 2.389199e+02 +1 266 -7.033400e+02 2.671000e+02 +4 266 9.623501e+02 3.564500e+02 +5 266 5.404700e+02 7.576899e+02 +6 266 -3.421500e+02 1.670300e+02 +0 267 6.964399e+02 2.080300e+02 +1 267 -6.779200e+02 1.977800e+02 +4 267 9.743101e+02 3.404900e+02 +5 267 5.601400e+02 7.380800e+02 +6 267 -3.175700e+02 1.182200e+02 +0 268 5.716001e+02 2.810801e+02 +1 268 -8.915900e+02 3.866799e+02 +5 268 4.506899e+02 7.703600e+02 +8 268 -6.898500e+02 3.960400e+02 +0 269 7.106299e+02 1.767500e+02 +1 269 -6.544200e+02 1.357300e+02 +4 269 9.825000e+02 3.223201e+02 +6 269 -2.996300e+02 7.381000e+01 +7 269 3.196899e+02 3.395500e+02 +13 269 -1.525030e+03 5.082900e+02 +0 270 5.663501e+02 2.752600e+02 +1 270 -9.022200e+02 3.766300e+02 +5 270 4.473000e+02 7.666899e+02 +8 270 -6.990100e+02 3.883000e+02 +0 271 5.636799e+02 2.824900e+02 +1 271 -9.067300e+02 3.913201e+02 +5 271 4.441400e+02 7.709900e+02 +8 271 -7.037300e+02 3.996600e+02 +0 272 5.602700e+02 3.922800e+02 +1 272 -9.075000e+02 6.242800e+02 +5 272 4.307500e+02 8.538700e+02 +8 272 -7.053200e+02 5.770000e+02 +0 273 4.673000e+02 4.032700e+02 +1 273 -1.098410e+03 6.782600e+02 +4 273 8.376799e+02 4.390701e+02 +8 273 -8.656700e+02 6.026600e+02 +0 274 5.285300e+02 6.906006e+01 +1 274 -9.853200e+02 -5.221997e+01 +0 275 5.602600e+02 2.458700e+02 +1 275 -9.159200e+02 3.167500e+02 +0 276 9.691299e+02 1.695400e+02 +1 276 -2.891600e+02 5.920996e+01 +4 276 1.161410e+03 3.370300e+02 +5 276 8.063799e+02 7.570400e+02 +6 276 2.357996e+01 5.809998e+00 +8 276 4.780029e+00 1.930800e+02 +16 276 6.236000e+02 3.594000e+02 +0 277 1.116810e+03 2.659600e+02 +1 277 -1.826300e+02 1.639399e+02 +6 277 1.660400e+02 6.467999e+01 +8 277 2.708400e+02 3.184900e+02 +13 277 -1.148910e+03 9.222000e+02 +16 277 6.879800e+02 4.403800e+02 +0 278 1.658000e+03 3.000300e+02 +1 278 1.134930e+03 3.254099e+02 +8 278 9.452100e+02 3.966899e+02 +17 278 -8.244700e+02 6.004500e+02 +0 279 1.664700e+03 2.213700e+02 +1 279 1.154650e+03 1.853301e+02 +6 279 9.762100e+02 9.159998e+01 +7 279 9.648401e+02 3.499399e+02 +8 279 9.554100e+02 2.782000e+02 +17 279 -8.104200e+02 4.829600e+02 +0 280 6.551101e+02 2.577200e+02 +1 280 -7.405200e+02 3.145100e+02 +3 280 -7.421700e+02 4.430000e+02 +7 280 2.934800e+02 3.937800e+02 +10 280 -2.036700e+02 -3.383300e+02 +11 280 3.746899e+02 2.220100e+02 +13 280 -1.594260e+03 7.324399e+02 +0 281 1.658980e+03 8.727002e+01 +1 281 1.150130e+03 -5.575000e+01 +6 281 9.662900e+02 -8.675000e+01 +7 281 9.589500e+02 2.628000e+02 +17 281 -8.207000e+02 2.802300e+02 +18 281 7.041003e+01 -4.893005e+01 +0 282 7.860000e+02 -3.045996e+01 +1 282 -5.350800e+02 -2.862100e+02 +3 282 -5.628500e+02 -1.988600e+02 +0 283 7.661799e+02 -3.339001e+01 +1 283 -5.638500e+02 -2.878700e+02 +4 283 1.014530e+03 2.025901e+02 +6 283 -2.386100e+02 -2.207400e+02 +0 284 7.961001e+02 3.990002e+01 +1 284 -5.173100e+02 -1.474700e+02 +5 284 6.588101e+02 6.241200e+02 +6 284 -1.924500e+02 -1.257100e+02 +0 285 1.654760e+03 3.413401e+02 +1 285 1.129210e+03 3.987800e+02 +8 285 9.405200e+02 4.588700e+02 +17 285 -8.285300e+02 6.669299e+02 +20 285 6.726001e+01 -1.311600e+02 +0 286 8.226599e+02 1.717400e+02 +1 286 -4.795000e+02 9.563000e+01 +4 286 1.055860e+03 3.271799e+02 +5 286 6.704301e+02 7.312700e+02 +6 286 -1.504100e+02 3.964001e+01 +0 287 1.330650e+03 1.641300e+02 +1 287 -4.081995e+01 -4.882996e+01 +8 287 6.163000e+02 1.509000e+02 +0 288 4.425100e+02 4.575000e+02 +1 288 -1.149050e+03 7.978500e+02 +4 288 8.241699e+02 4.694299e+02 +5 288 3.351899e+02 8.868600e+02 +8 288 -9.030200e+02 6.909399e+02 +0 289 4.425100e+02 4.575000e+02 +1 289 -1.149050e+03 7.978500e+02 +5 289 3.351899e+02 8.868600e+02 +0 290 4.934399e+02 4.723201e+02 +1 290 -1.040590e+03 8.108300e+02 +0 291 6.148000e+02 3.340601e+02 +1 291 -8.114200e+02 4.823000e+02 +7 291 2.721200e+02 4.477200e+02 +0 292 6.230801e+02 3.445701e+02 +1 292 -7.956100e+02 4.997600e+02 +4 292 9.300601e+02 4.148600e+02 +5 292 4.861200e+02 8.295400e+02 +8 292 -5.942800e+02 4.941500e+02 +0 293 1.138150e+03 2.186000e+02 +1 293 -1.431400e+02 8.953003e+01 +8 293 2.963500e+02 2.493200e+02 +0 294 8.254399e+02 -4.900000e+01 +1 294 -4.854500e+02 -3.254100e+02 +0 295 7.318301e+02 1.727200e+02 +1 295 -6.180200e+02 1.211899e+02 +0 296 7.548201e+02 -5.001001e+01 +1 296 -5.824800e+02 -3.207500e+02 +4 296 1.007440e+03 1.924299e+02 +6 296 -2.544800e+02 -2.426800e+02 +0 297 8.981201e+02 1.172600e+02 +1 297 -3.742200e+02 -1.846997e+01 +5 297 7.427800e+02 7.012600e+02 +8 297 -1.195800e+02 1.161900e+02 +0 298 6.940601e+02 1.213600e+02 +1 298 -6.819800e+02 2.575000e+01 +6 298 -3.307700e+02 5.700073e-01 +0 299 1.326450e+03 1.743401e+02 +1 299 -4.682996e+01 -3.316003e+01 +8 299 6.085200e+02 1.658200e+02 +0 300 1.326450e+03 1.743401e+02 +1 300 -4.682996e+01 -3.316003e+01 +8 300 6.085200e+02 1.658200e+02 +0 301 9.235901e+02 9.255005e+01 +1 301 -3.400200e+02 -6.784998e+01 +4 301 1.124940e+03 2.851500e+02 +8 301 -7.628998e+01 7.635999e+01 +0 302 8.613201e+02 2.951799e+02 +1 302 -4.191600e+02 3.163000e+02 +4 302 1.084450e+03 4.036100e+02 +5 302 6.924900e+02 8.352700e+02 +8 302 -1.806800e+02 3.956400e+02 +0 303 8.469299e+02 1.318401e+02 +1 303 -4.465000e+02 1.657001e+01 +4 303 1.072110e+03 3.049000e+02 +8 303 -2.058400e+02 1.417000e+02 +0 304 8.546699e+02 2.838201e+02 +1 304 -4.273000e+02 3.006100e+02 +3 304 -4.886800e+02 4.098700e+02 +4 304 1.079670e+03 3.958900e+02 +5 304 6.877200e+02 8.249500e+02 +6 304 -1.032100e+02 1.774300e+02 +8 304 -1.921100e+02 3.783000e+02 +13 304 -1.280930e+03 8.488300e+02 +0 305 8.598601e+02 2.891400e+02 +1 305 -4.203000e+02 3.075100e+02 +4 305 1.083380e+03 4.000400e+02 +5 305 6.918600e+02 8.299299e+02 +6 305 -9.664001e+01 1.830400e+02 +7 305 3.967600e+02 4.316000e+02 +8 305 -1.821900e+02 3.852800e+02 +0 306 7.478101e+02 5.301001e+01 +1 306 -5.931300e+02 -1.170200e+02 +4 306 1.004630e+03 2.518101e+02 +5 306 6.170699e+02 6.267600e+02 +0 307 7.549600e+02 1.207000e+02 +1 307 -5.792200e+02 1.320001e+01 +5 307 6.164800e+02 6.801100e+02 +0 308 6.003000e+02 3.524399e+02 +1 308 -8.360700e+02 5.231700e+02 +3 308 -8.303200e+02 6.728800e+02 +8 308 -6.329400e+02 5.101500e+02 +0 309 1.654070e+03 2.379199e+02 +1 309 1.138420e+03 2.157500e+02 +7 309 9.591101e+02 3.606699e+02 +17 309 -8.240500e+02 5.085901e+02 +0 310 4.659199e+02 4.442700e+02 +1 310 -1.097020e+03 7.637100e+02 +7 310 1.894000e+02 5.205901e+02 +0 311 4.536499e+02 3.907500e+02 +1 311 -1.128680e+03 6.528400e+02 +4 311 8.302600e+02 4.320000e+02 +10 311 -2.959500e+02 -2.581801e+02 +0 312 1.517290e+03 2.058101e+02 +1 312 8.709600e+02 1.564900e+02 +7 312 8.710200e+02 3.454800e+02 +0 313 1.523240e+03 2.995300e+02 +1 313 8.759199e+02 3.238401e+02 +17 313 -1.050290e+03 6.278900e+02 +0 314 1.523240e+03 2.995300e+02 +1 314 8.759199e+02 3.238401e+02 +17 314 -1.050290e+03 6.278900e+02 +0 315 1.542540e+03 1.484600e+02 +1 315 9.180500e+02 5.208008e+01 +3 315 9.682600e+02 1.579900e+02 +0 316 4.701399e+02 3.588600e+02 +1 316 -1.094810e+03 5.819000e+02 +0 317 1.487390e+03 2.462400e+02 +1 317 7.458000e+02 2.118900e+02 +6 317 6.999600e+02 1.090000e+02 +8 317 7.220100e+02 3.115400e+02 +17 317 -1.188350e+03 5.652800e+02 +0 318 1.326460e+03 1.669500e+02 +1 318 -4.683997e+01 -4.495996e+01 +6 318 3.205500e+02 -8.839001e+01 +8 318 6.088000e+02 1.547900e+02 +16 318 7.979500e+02 4.080400e+02 +0 319 1.330560e+03 1.695100e+02 +1 319 -4.183997e+01 -4.170996e+01 +8 319 6.149399e+02 1.582000e+02 +0 320 1.354970e+03 7.619995e+00 +1 320 -1.589966e+00 -2.718500e+02 +8 320 6.445200e+02 -7.002002e+01 +0 321 8.981699e+02 2.044399e+02 +1 321 -3.728199e+02 1.415200e+02 +4 321 1.109250e+03 3.517500e+02 +8 321 -1.175100e+02 2.510000e+02 +0 322 6.961699e+02 1.608700e+02 +1 322 -6.747700e+02 1.046200e+02 +0 323 6.718501e+02 2.085500e+02 +1 323 -7.190200e+02 2.061500e+02 +0 324 8.323501e+02 -6.920996e+01 +1 324 -4.708800e+02 -3.610000e+02 +6 324 -1.522900e+02 -2.752600e+02 +0 325 8.091101e+02 2.804004e+01 +1 325 -4.995200e+02 -1.754700e+02 +3 325 -5.390900e+02 -8.175000e+01 +6 325 -1.776600e+02 -1.449100e+02 +0 326 8.502800e+02 2.519500e+02 +1 326 -4.370300e+02 2.397900e+02 +3 326 -4.986400e+02 3.458900e+02 +4 326 1.076470e+03 3.771599e+02 +5 326 6.878600e+02 7.992100e+02 +6 326 -1.098300e+02 1.366300e+02 +8 326 -1.982700e+02 3.280800e+02 +0 327 6.122600e+02 1.559399e+02 +1 327 -8.228400e+02 1.160400e+02 +0 328 9.908301e+02 9.171997e+01 +1 328 -2.666899e+02 -7.746997e+01 +16 328 6.332200e+02 3.175800e+02 +0 329 7.086101e+02 1.938000e+02 +1 329 -6.570400e+02 1.665400e+02 +4 329 9.816799e+02 3.327900e+02 +5 329 5.717700e+02 7.297600e+02 +7 329 3.183500e+02 3.509800e+02 +0 330 8.379900e+02 1.175000e+01 +1 330 -4.601600e+02 -2.065601e+02 +0 331 8.248101e+02 1.954099e+02 +1 331 -4.767100e+02 1.425901e+02 +3 331 -5.287900e+02 2.481400e+02 +4 331 1.056600e+03 3.414600e+02 +5 331 6.689100e+02 7.501000e+02 +0 332 8.559900e+02 2.366899e+02 +1 332 -4.300000e+02 2.110000e+02 +3 332 -4.929100e+02 3.164600e+02 +6 332 -1.049900e+02 1.165600e+02 +7 332 3.930699e+02 3.930601e+02 +8 332 -1.893600e+02 3.039399e+02 +13 332 -1.292220e+03 7.077800e+02 +0 333 5.408301e+02 3.745601e+02 +1 333 -9.459300e+02 5.933600e+02 +0 334 5.340801e+02 2.511699e+02 +1 334 -9.696500e+02 3.342600e+02 +5 334 4.244301e+02 7.430000e+02 +8 334 -7.554900e+02 3.507800e+02 +0 335 1.594090e+03 1.466300e+02 +1 335 1.028050e+03 5.116992e+01 +3 335 1.090810e+03 1.577800e+02 +8 335 8.581801e+02 1.648900e+02 +17 335 -9.190300e+02 3.747600e+02 +0 336 7.616001e+02 9.125000e+01 +1 336 -5.686100e+02 -4.403003e+01 +3 336 -5.930700e+02 5.715002e+01 +0 337 5.841101e+02 3.585500e+02 +1 337 -8.663400e+02 5.437900e+02 +8 337 -6.641700e+02 5.201100e+02 +0 338 4.533101e+02 4.287900e+02 +1 338 -1.124870e+03 7.353600e+02 +8 338 -8.879800e+02 6.446000e+02 +9 338 -3.943900e+02 4.270601e+02 +0 339 4.725400e+02 3.356300e+02 +1 339 -1.090490e+03 5.316100e+02 +3 339 -1.074460e+03 6.935800e+02 +0 340 5.078201e+02 8.659998e+01 +1 340 -1.029290e+03 -1.296997e+01 +3 340 -1.002840e+03 1.011300e+02 +0 341 4.726001e+02 3.418401e+02 +1 341 -1.089540e+03 5.442900e+02 +3 341 -1.074480e+03 7.074000e+02 +0 342 1.584600e+03 2.243301e+02 +1 342 1.013700e+03 1.929700e+02 +3 342 1.078750e+03 3.028900e+02 +6 342 8.692900e+02 9.878998e+01 +8 342 8.443000e+02 2.837100e+02 +0 343 7.860000e+02 -3.045996e+01 +1 343 -5.350800e+02 -2.862100e+02 +0 344 6.783301e+02 1.103400e+02 +1 344 -7.088300e+02 8.059998e+00 +0 345 7.055200e+02 1.784099e+02 +1 345 -6.635000e+02 1.372700e+02 +6 345 -3.064800e+02 7.526001e+01 +0 346 6.500300e+02 2.743600e+02 +1 346 -7.503500e+02 3.470000e+02 +5 346 5.147400e+02 7.799000e+02 +0 347 6.766499e+02 2.834099e+02 +1 347 -7.057300e+02 3.559000e+02 +5 347 5.357900e+02 7.910701e+02 +0 348 7.657600e+02 2.318600e+02 +1 348 -5.584700e+02 2.294900e+02 +0 349 5.925300e+02 4.235300e+02 +1 349 -8.473500e+02 6.736300e+02 +5 349 4.530300e+02 8.843101e+02 +0 350 6.295500e+02 2.330801e+02 +1 350 -7.895500e+02 2.701400e+02 +0 351 1.660470e+03 9.031006e+01 +1 351 1.151700e+03 -5.003003e+01 +6 351 9.676500e+02 -8.256000e+01 +8 351 9.495200e+02 7.954999e+01 +17 351 -8.179700e+02 2.847600e+02 +0 352 1.684920e+03 2.470500e+02 +1 352 1.187350e+03 2.312800e+02 +8 352 9.825100e+02 3.167300e+02 +0 353 1.662640e+03 4.607300e+02 +1 353 8.207700e+02 4.969500e+02 +0 354 1.597000e+03 8.162000e+01 +1 354 1.036400e+03 -6.682996e+01 +8 354 8.631899e+02 6.569000e+01 +17 354 -9.136800e+02 2.741400e+02 +0 355 5.717400e+02 4.049399e+02 +1 355 -8.847000e+02 6.444200e+02 +0 356 6.003601e+02 1.031500e+02 +1 356 -8.478200e+02 5.789978e+00 +5 356 4.914200e+02 6.413500e+02 +0 357 5.184800e+02 2.431400e+02 +1 357 -1.001620e+03 3.167600e+02 +5 357 4.132200e+02 7.351799e+02 +8 357 -7.815900e+02 3.366600e+02 +0 358 7.565500e+02 -7.168005e+01 +1 358 -5.777400e+02 -3.639700e+02 +0 359 1.567610e+03 1.071400e+02 +1 359 9.798101e+02 -2.127002e+01 +0 360 5.922500e+02 3.328800e+02 +1 360 -8.526400e+02 4.821000e+02 +8 360 -6.501700e+02 4.765800e+02 +0 361 5.115100e+02 1.820601e+02 +1 361 -1.019350e+03 1.923700e+02 +0 362 6.242500e+02 2.369199e+02 +1 362 -7.992600e+02 2.790300e+02 +0 363 4.842300e+02 2.680300e+02 +1 363 -1.068850e+03 3.831400e+02 +4 363 8.466201e+02 3.634399e+02 +0 364 4.753601e+02 2.850701e+02 +1 364 -1.088510e+03 4.208700e+02 +0 365 6.505400e+02 5.848999e+01 +1 365 -7.581200e+02 -9.113000e+01 +0 366 7.205601e+02 7.680005e+01 +1 366 -6.388700e+02 -6.681006e+01 +5 366 5.922500e+02 6.410900e+02 +0 367 6.408799e+02 9.641003e+01 +1 367 -7.717100e+02 -1.271002e+01 +0 368 6.397300e+02 1.020200e+02 +1 368 -7.737200e+02 -1.210022e+00 +0 369 5.643799e+02 1.096500e+02 +1 369 -9.130400e+02 2.937000e+01 +4 369 8.919700e+02 2.768301e+02 +0 370 5.741201e+02 1.481300e+02 +1 370 -8.935900e+02 1.073101e+02 +5 370 4.663000e+02 6.720200e+02 +0 371 5.809199e+02 1.826200e+02 +1 371 -8.804400e+02 1.787500e+02 +0 372 5.330901e+02 2.517500e+02 +1 372 -9.721800e+02 3.352900e+02 +0 373 5.249500e+02 2.859000e+02 +1 373 -9.837100e+02 4.123900e+02 +4 373 8.705701e+02 3.750601e+02 +5 373 4.145400e+02 7.684000e+02 +8 373 -7.707900e+02 4.083600e+02 +0 374 5.086699e+02 3.122600e+02 +1 374 -1.012630e+03 4.748101e+02 +4 374 8.603601e+02 3.880801e+02 +5 374 3.981200e+02 7.848500e+02 +8 374 -8.012500e+02 4.530400e+02 +0 375 5.733899e+02 3.759299e+02 +1 375 -8.837000e+02 5.828000e+02 +4 375 8.999099e+02 4.285901e+02 +5 375 4.430100e+02 8.442300e+02 +0 376 5.741699e+02 3.899099e+02 +1 376 -8.809200e+02 6.137200e+02 +8 376 -6.822500e+02 5.726200e+02 +0 377 8.375400e+02 -9.288000e+01 +1 377 -4.615400e+02 -4.064000e+02 +0 378 6.499700e+02 1.278000e+02 +1 378 -7.561800e+02 4.729004e+01 +0 379 5.830200e+02 1.446500e+02 +1 379 -8.785500e+02 9.923999e+01 +4 379 9.034600e+02 2.971899e+02 +5 379 4.738101e+02 6.699700e+02 +6 379 -4.908600e+02 5.731000e+01 +0 380 5.448799e+02 1.512500e+02 +1 380 -9.500000e+02 1.209099e+02 +4 380 8.803999e+02 2.990801e+02 +0 381 1.330650e+03 1.641300e+02 +1 381 -4.081995e+01 -4.882996e+01 +0 382 8.426599e+02 1.728600e+02 +1 382 -4.460300e+02 9.692993e+01 +6 382 -1.248700e+02 3.954999e+01 +0 383 5.421001e+02 1.878401e+02 +1 383 -9.534500e+02 1.986699e+02 +4 383 8.792000e+02 3.198101e+02 +6 383 -5.489900e+02 1.290100e+02 +8 383 -7.425900e+02 2.474900e+02 +0 384 8.945100e+02 1.986400e+02 +1 384 -3.802300e+02 1.305400e+02 +8 384 -1.239000e+02 2.416800e+02 +0 385 1.123440e+03 2.203800e+02 +1 385 -1.650500e+02 9.334998e+01 +0 386 1.671960e+03 2.225801e+02 +1 386 1.165450e+03 1.873000e+02 +0 387 5.850601e+02 2.329299e+02 +1 387 -8.698100e+02 2.823201e+02 +0 388 5.886299e+02 2.453201e+02 +1 388 -8.610300e+02 3.078900e+02 +0 389 8.249600e+02 2.916100e+02 +1 389 -4.767500e+02 3.213101e+02 +8 389 -2.407500e+02 3.919000e+02 +0 390 4.674800e+02 3.158700e+02 +1 390 -1.101020e+03 4.933600e+02 +5 390 3.676400e+02 7.825601e+02 +8 390 -8.715600e+02 4.611799e+02 +0 391 5.654900e+02 3.337800e+02 +1 391 -8.993200e+02 4.995800e+02 +0 392 6.359299e+02 3.348700e+02 +1 392 -7.704100e+02 4.743101e+02 +0 393 8.291399e+02 3.358700e+02 +1 393 -4.707100e+02 4.018101e+02 +8 393 -2.325800e+02 4.606400e+02 +0 394 5.598000e+02 3.836699e+02 +1 394 -9.095000e+02 6.053400e+02 +8 394 -7.072000e+02 5.633800e+02 +0 395 5.345500e+02 4.449900e+02 +1 395 -9.564200e+02 7.427500e+02 +0 396 7.869800e+02 -9.755005e+01 +1 396 -5.349300e+02 -4.148400e+02 +6 396 -2.152600e+02 -3.092700e+02 +0 397 5.715400e+02 8.818005e+01 +1 397 -8.996700e+02 -1.745001e+01 +0 398 1.655630e+03 9.390002e+01 +1 398 1.143970e+03 -4.401001e+01 +8 398 9.440601e+02 8.412000e+01 +0 399 1.150610e+03 1.298201e+02 +1 399 -1.233600e+02 -5.404004e+01 +5 399 1.005330e+03 7.665100e+02 +8 399 3.144200e+02 1.173600e+02 +0 400 5.603101e+02 1.410601e+02 +1 400 -9.203700e+02 9.890002e+01 +0 401 6.031499e+02 1.459000e+02 +1 401 -8.401100e+02 9.631006e+01 +0 402 1.556130e+03 1.872400e+02 +1 402 9.497100e+02 1.243101e+02 +0 403 8.994600e+02 1.909900e+02 +1 403 -3.710000e+02 1.147300e+02 +8 403 -1.159900e+02 2.295400e+02 +0 404 5.816001e+02 2.031400e+02 +1 404 -8.775300e+02 2.212300e+02 +0 405 5.147000e+02 2.798201e+02 +1 405 -1.006610e+03 4.004299e+02 +0 406 6.293401e+02 3.449399e+02 +1 406 -7.845500e+02 4.971500e+02 +5 406 4.913400e+02 8.314600e+02 +0 407 5.466399e+02 3.992000e+02 +1 407 -9.333300e+02 6.440300e+02 +0 408 5.573501e+02 4.228900e+02 +1 408 -9.114000e+02 6.877800e+02 +0 409 4.960000e+02 4.254800e+02 +1 409 -1.037020e+03 7.128300e+02 +8 409 -8.141100e+02 6.353000e+02 +0 410 8.214800e+02 -7.738000e+01 +1 410 -4.866300e+02 -3.755500e+02 +6 410 -1.678600e+02 -2.855800e+02 +0 411 1.402410e+03 -1.952002e+01 +1 411 3.882996e+01 -3.125900e+02 +0 412 1.353560e+03 2.727002e+01 +1 412 -4.219971e+00 -2.441400e+02 +6 412 3.428900e+02 -2.236200e+02 +8 412 6.426400e+02 -4.254999e+01 +0 413 5.902500e+02 1.590801e+02 +1 413 -8.628200e+02 1.277400e+02 +0 414 7.976299e+02 1.726000e+02 +1 414 -5.126600e+02 1.076000e+02 +0 415 5.504800e+02 2.696799e+02 +1 415 -9.332800e+02 3.691699e+02 +0 416 5.025701e+02 3.294900e+02 +1 416 -1.028640e+03 5.087600e+02 +0 417 4.857600e+02 4.263301e+02 +1 417 -1.058390e+03 7.181899e+02 +0 418 -1.198440e+03 6.713300e+02 +4 418 -5.596997e+01 5.465900e+02 +7 418 -9.806800e+02 7.094299e+02 +10 418 -1.353770e+03 -1.918005e+01 +14 418 -1.267200e+02 4.621700e+02 +15 418 6.909399e+02 4.390601e+02 +16 418 -5.188800e+02 5.841100e+02 +20 418 -1.239650e+03 8.368994e+01 +0 419 1.590530e+03 2.648101e+02 +7 419 9.200601e+02 3.794399e+02 +0 420 -1.043300e+03 4.905400e+02 +4 420 2.080005e+01 4.568500e+02 +10 420 -1.268070e+03 -1.589200e+02 +0 421 -1.205470e+03 5.070901e+02 +4 421 -5.558997e+01 4.599299e+02 +0 422 6.567600e+02 4.271000e+02 +8 422 -5.307900e+02 6.123101e+02 +0 423 5.212100e+02 4.324900e+02 +5 423 3.974301e+02 8.803199e+02 +0 424 -2.340200e+02 1.011930e+03 +7 424 6.180601e+02 4.348101e+02 +9 424 5.173601e+02 2.064700e+02 +10 424 3.458101e+02 -2.975500e+02 +16 424 5.224399e+02 4.344200e+02 +17 424 2.016400e+02 7.189500e+02 +18 424 2.033997e+01 1.709961e+00 +20 424 3.022998e+01 -1.948000e+02 +0 425 -2.340200e+02 1.011930e+03 +7 425 6.180601e+02 4.348101e+02 +9 425 5.173601e+02 2.064700e+02 +10 425 3.458101e+02 -2.975500e+02 +12 425 -3.776200e+02 -5.175300e+02 +16 425 5.224399e+02 4.344200e+02 +17 425 2.016400e+02 7.189500e+02 +18 425 2.033997e+01 1.709961e+00 +20 425 3.022998e+01 -1.948000e+02 +0 426 -1.470230e+03 1.906899e+02 +4 426 -1.794800e+02 2.914500e+02 +5 426 -9.830500e+02 4.483900e+02 +14 426 -2.442200e+02 2.409700e+02 +15 426 5.437900e+02 1.501000e+02 +19 426 1.454500e+02 2.170701e+02 +0 427 6.319800e+02 3.125901e+02 +4 427 9.365100e+02 3.995000e+02 +5 427 4.992300e+02 8.116500e+02 +0 428 7.451799e+02 3.168401e+02 +4 428 1.013050e+03 4.156400e+02 +5 428 6.030400e+02 8.386400e+02 +0 429 6.013501e+02 3.473000e+02 +2 429 -2.621700e+02 2.928300e+02 +4 429 9.162200e+02 4.119600e+02 +5 429 4.685699e+02 8.248700e+02 +7 429 2.641700e+02 4.544900e+02 +9 429 -3.022400e+02 3.643600e+02 +10 429 -2.283199e+02 -2.830000e+02 +11 429 3.453600e+02 2.957400e+02 +12 429 -8.458700e+02 -3.823500e+02 +18 429 -4.608400e+02 1.095701e+02 +0 430 -1.628920e+03 4.183600e+02 +4 430 -2.696500e+02 4.120801e+02 +0 431 -1.058030e+03 7.076100e+02 +4 431 1.005005e+01 5.726500e+02 +7 431 -8.890100e+02 7.417200e+02 +10 431 -1.269280e+03 6.050049e+00 +14 431 -7.197000e+01 4.778201e+02 +16 431 -4.508400e+02 6.106100e+02 +19 431 5.023101e+02 7.476200e+02 +0 432 -1.215310e+03 7.279399e+02 +4 432 -6.463000e+01 5.764900e+02 +5 432 -8.906100e+02 8.680800e+02 +7 432 -9.970100e+02 7.553900e+02 +10 432 -1.367730e+03 2.402002e+01 +14 432 -1.344200e+02 4.888700e+02 +16 432 -5.323300e+02 6.166899e+02 +20 432 -1.254290e+03 1.179700e+02 +0 433 7.447300e+02 7.239001e+01 +4 433 1.002440e+03 2.621400e+02 +0 434 1.534850e+03 2.134900e+02 +7 434 8.805801e+02 3.510901e+02 +0 435 1.527810e+03 2.400400e+02 +8 435 7.694800e+02 3.056600e+02 +16 435 9.464200e+02 3.818800e+02 +0 436 8.212500e+02 2.473500e+02 +4 436 1.056490e+03 3.719199e+02 +5 436 6.622800e+02 7.907500e+02 +0 437 1.527000e+03 2.785801e+02 +7 437 8.780200e+02 3.939700e+02 +8 437 7.677400e+02 3.652000e+02 +16 437 9.458700e+02 4.017300e+02 +0 438 1.662010e+03 3.278800e+02 +7 438 9.650601e+02 4.194800e+02 +12 438 -1.684399e+02 -4.335100e+02 +0 439 -9.089400e+02 3.549299e+02 +4 439 8.492004e+01 3.895701e+02 +7 439 -7.936300e+02 4.593700e+02 +14 439 -2.073999e+01 3.099300e+02 +15 439 8.432300e+02 2.590701e+02 +16 439 -3.703000e+02 4.118600e+02 +18 439 -1.315350e+03 1.214099e+02 +19 439 6.411299e+02 3.953101e+02 +0 440 -1.208080e+03 4.824099e+02 +7 440 -9.829000e+02 5.552700e+02 +16 440 -5.185000e+02 4.736100e+02 +19 440 3.765800e+02 5.111300e+02 +0 441 -9.093800e+02 6.781200e+02 +7 441 -7.997800e+02 7.207800e+02 +14 441 -1.962000e+01 4.624800e+02 +15 441 8.386300e+02 4.606400e+02 +16 441 -3.802700e+02 6.002300e+02 +19 441 6.285701e+02 7.272900e+02 +0 442 -1.015370e+03 7.011000e+02 +4 442 3.044995e+01 5.707300e+02 +10 442 -1.244220e+03 -1.500244e-01 +15 442 7.845200e+02 4.672500e+02 +0 443 -1.183280e+03 7.254100e+02 +4 443 -5.244995e+01 5.760701e+02 +5 443 -8.731100e+02 8.699301e+02 +14 443 -1.214200e+02 4.872400e+02 +15 443 6.928300e+02 4.724700e+02 +0 444 -1.356870e+03 7.405200e+02 +4 444 -1.346700e+02 5.782900e+02 +14 444 -1.949900e+02 4.970601e+02 +15 444 5.977500e+02 4.734900e+02 +16 444 -6.093600e+02 6.202900e+02 +0 445 -9.888100e+02 7.440200e+02 +4 445 3.528003e+01 5.984399e+02 +15 445 7.857300e+02 4.989900e+02 +16 445 -4.305600e+02 6.395400e+02 +19 445 5.445200e+02 7.909000e+02 +0 446 -1.586820e+03 7.590800e+02 +4 446 -2.596700e+02 5.852800e+02 +5 446 -1.163340e+03 8.406799e+02 +14 446 -3.155100e+02 5.086400e+02 +19 446 -3.119995e+00 7.548500e+02 +0 447 -1.586820e+03 7.590800e+02 +4 447 -2.596700e+02 5.852800e+02 +5 447 -1.163340e+03 8.406799e+02 +14 447 -3.155100e+02 5.086400e+02 +16 447 -7.595700e+02 6.308300e+02 +19 447 -3.119995e+00 7.548500e+02 +0 448 -1.278210e+03 7.639700e+02 +4 448 -9.867004e+01 5.941100e+02 +5 448 -9.416800e+02 8.860900e+02 +15 448 6.388000e+02 4.917800e+02 +16 448 -5.694700e+02 6.367500e+02 +0 449 -1.615360e+03 7.782900e+02 +4 449 -2.774600e+02 5.977400e+02 +5 449 -1.185940e+03 8.533700e+02 +15 449 4.347900e+02 4.863201e+02 +0 450 -1.271280e+03 7.897700e+02 +4 450 -9.990002e+01 6.093201e+02 +5 450 -9.461100e+02 9.083101e+02 +10 450 -1.427250e+03 7.580005e+01 +14 450 -1.675200e+02 5.196100e+02 +15 450 6.346300e+02 5.081799e+02 +16 450 -5.746100e+02 6.535100e+02 +0 451 -1.166730e+03 8.330000e+02 +4 451 -4.516003e+01 6.370200e+02 +14 451 -1.155000e+02 5.370900e+02 +0 452 -1.429350e+03 9.749600e+02 +4 452 -1.872500e+02 7.070100e+02 +0 453 -1.190590e+03 4.502002e+01 +4 453 -3.960999e+01 2.212400e+02 +7 453 -9.533700e+02 2.149900e+02 +15 453 7.021300e+02 6.915002e+01 +0 454 7.053799e+02 7.862000e+01 +4 454 9.778899e+02 2.657100e+02 +0 455 -1.484660e+03 1.415601e+02 +4 455 -1.856400e+02 2.664399e+02 +5 455 -9.845700e+02 4.140000e+02 +19 455 1.333800e+02 1.690300e+02 +0 456 -1.464380e+03 1.611500e+02 +4 456 -1.778400e+02 2.779000e+02 +5 456 -9.727900e+02 4.274199e+02 +15 456 5.467400e+02 1.331200e+02 +16 456 -6.445100e+02 2.850800e+02 +0 457 7.009800e+02 1.956699e+02 +4 457 9.754299e+02 3.329399e+02 +5 457 5.581300e+02 7.272800e+02 +0 458 9.412700e+02 1.977600e+02 +4 458 1.141300e+03 3.519000e+02 +5 458 7.773101e+02 7.742300e+02 +8 458 -4.160999e+01 2.363200e+02 +0 459 -1.571510e+03 1.976599e+02 +4 459 -2.336700e+02 2.951400e+02 +5 459 -1.054280e+03 4.416200e+02 +0 460 6.015500e+02 2.050601e+02 +4 460 9.149399e+02 3.324800e+02 +5 460 4.820699e+02 7.170500e+02 +0 461 6.015500e+02 2.050601e+02 +4 461 9.149399e+02 3.324800e+02 +5 461 4.820699e+02 7.170500e+02 +0 462 -1.417160e+03 2.189399e+02 +4 462 -1.543101e+02 3.070300e+02 +5 462 -9.485200e+02 4.760900e+02 +0 463 -1.417160e+03 2.189399e+02 +4 463 -1.543101e+02 3.070300e+02 +5 463 -9.485200e+02 4.760900e+02 +19 463 1.920601e+02 2.456500e+02 +0 464 -1.585180e+03 2.180601e+02 +4 464 -2.407300e+02 3.052100e+02 +5 464 -1.067410e+03 4.548301e+02 +14 464 -3.043500e+02 2.550500e+02 +15 464 4.700300e+02 1.659800e+02 +16 464 -7.238300e+02 3.167500e+02 +19 464 2.841003e+01 2.384700e+02 +0 465 -1.585180e+03 2.180601e+02 +4 465 -2.407300e+02 3.052100e+02 +14 465 -3.043500e+02 2.550500e+02 +16 465 -7.238300e+02 3.167500e+02 +19 465 2.841003e+01 2.384700e+02 +0 466 -8.445100e+02 2.332600e+02 +4 466 1.138600e+02 3.262200e+02 +7 466 -7.619200e+02 3.646799e+02 +14 466 -3.609985e+00 2.528500e+02 +15 466 8.730000e+02 1.869300e+02 +16 466 -3.412200e+02 3.442100e+02 +0 467 -8.445100e+02 2.332600e+02 +4 467 1.138600e+02 3.262200e+02 +7 467 -7.619200e+02 3.646799e+02 +10 467 -1.180740e+03 -3.522500e+02 +14 467 -3.609985e+00 2.528500e+02 +15 467 8.730000e+02 1.869300e+02 +16 467 -3.412200e+02 3.442100e+02 +0 468 7.194700e+02 2.633401e+02 +4 468 9.903201e+02 3.727800e+02 +5 468 5.746200e+02 7.827700e+02 +7 468 3.264100e+02 4.019000e+02 +0 469 5.713301e+02 2.942700e+02 +4 469 8.979800e+02 3.808600e+02 +5 469 4.497000e+02 7.813600e+02 +0 470 1.523240e+03 3.084600e+02 +7 470 8.755300e+02 4.140300e+02 +12 470 -2.517500e+02 -4.341899e+02 +16 470 9.437800e+02 4.179000e+02 +0 471 1.563260e+03 3.184000e+02 +7 471 9.037500e+02 4.185400e+02 +8 471 8.146200e+02 4.264700e+02 +16 471 9.671200e+02 4.226100e+02 +0 472 -8.830400e+02 3.521400e+02 +4 472 9.567004e+01 3.889000e+02 +7 472 -7.829400e+02 4.590901e+02 +14 472 -1.379001e+01 3.089300e+02 +16 472 -3.603100e+02 4.111200e+02 +19 472 6.593899e+02 3.938900e+02 +0 473 5.538000e+02 3.613000e+02 +4 473 8.885000e+02 4.177900e+02 +0 474 6.076599e+02 3.965300e+02 +4 474 9.220400e+02 4.421899e+02 +5 474 4.696000e+02 8.657000e+02 +8 474 -6.178100e+02 5.787300e+02 +0 475 -8.543700e+02 4.154600e+02 +4 475 1.081500e+02 4.269700e+02 +7 475 -7.685500e+02 5.148800e+02 +10 475 -1.178670e+03 -2.079500e+02 +14 475 -4.750000e+00 3.400600e+02 +15 475 8.673700e+02 3.034000e+02 +0 476 5.120200e+02 4.566300e+02 +4 476 8.642700e+02 4.718600e+02 +5 476 3.872300e+02 8.954200e+02 +0 477 -1.124590e+03 4.553600e+02 +4 477 -1.708997e+01 4.363500e+02 +7 477 -9.263400e+02 5.374000e+02 +10 477 -1.318190e+03 -1.820500e+02 +14 477 -9.781000e+01 3.604900e+02 +15 477 7.303600e+02 3.139700e+02 +16 477 -4.763800e+02 4.626600e+02 +19 477 4.520200e+02 4.901799e+02 +0 478 -1.226260e+03 4.637000e+02 +4 478 -6.493994e+01 4.368600e+02 +5 478 -8.595700e+02 6.748400e+02 +7 478 -9.955600e+02 5.424900e+02 +14 478 -1.389500e+02 3.656700e+02 +15 478 6.761700e+02 3.149100e+02 +16 478 -5.271300e+02 4.636300e+02 +19 478 3.601200e+02 4.935000e+02 +0 479 -7.374500e+02 6.388401e+02 +4 479 1.509700e+02 5.604800e+02 +0 480 -1.560180e+03 6.556400e+02 +4 480 -2.401100e+02 5.307100e+02 +5 480 -1.122390e+03 7.686400e+02 +10 480 -1.654230e+03 -9.410034e+00 +14 480 -2.958600e+02 4.591100e+02 +15 480 4.761500e+02 4.184000e+02 +16 480 -7.283800e+02 5.695900e+02 +19 480 3.676001e+01 6.590200e+02 +0 481 -8.926100e+02 7.004900e+02 +4 481 8.489001e+01 5.788000e+02 +5 481 -6.717300e+02 8.973900e+02 +15 481 8.426500e+02 4.775800e+02 +16 481 -3.778300e+02 6.158201e+02 +19 481 6.365400e+02 7.512100e+02 +0 482 -1.297220e+03 8.013201e+02 +4 482 -1.120300e+02 6.158101e+02 +0 483 -1.466830e+03 8.128101e+02 +4 483 -1.962100e+02 6.155900e+02 +5 483 -1.084480e+03 8.969800e+02 +10 483 -1.571870e+03 1.091200e+02 +14 483 -2.536800e+02 5.332100e+02 +15 483 5.247600e+02 5.128600e+02 +16 483 -6.833900e+02 6.631100e+02 +19 483 1.159399e+02 8.181799e+02 +20 483 -1.415410e+03 1.810100e+02 +0 484 -1.425430e+03 8.393900e+02 +4 484 -1.747900e+02 6.288700e+02 +5 484 -1.057760e+03 9.217100e+02 +16 484 -6.569900e+02 6.778700e+02 +19 484 1.580000e+02 8.482100e+02 +0 485 -1.425430e+03 8.393900e+02 +4 485 -1.747900e+02 6.288700e+02 +5 485 -1.057760e+03 9.217100e+02 +14 485 -2.323700e+02 5.449000e+02 +16 485 -6.569900e+02 6.778700e+02 +19 485 1.580000e+02 8.482100e+02 +0 486 -1.397070e+03 9.166201e+02 +4 486 -1.692000e+02 6.739900e+02 +16 486 -6.575900e+02 7.278000e+02 +0 487 7.719700e+02 2.515002e+01 +4 487 1.018890e+03 2.364099e+02 +6 487 -2.266000e+02 -1.412600e+02 +0 488 -1.363380e+03 2.876001e+01 +7 488 -1.081770e+03 1.990200e+02 +16 488 -5.838900e+02 2.149900e+02 +0 489 -1.055350e+03 6.429004e+01 +4 489 2.306995e+01 2.335901e+02 +7 489 -8.655100e+02 2.324399e+02 +14 489 -6.975000e+01 1.804000e+02 +15 489 7.749000e+02 8.201001e+01 +16 489 -4.245700e+02 2.436800e+02 +20 489 -1.183230e+03 -2.645900e+02 +0 490 -1.205570e+03 6.876001e+01 +4 490 -4.718005e+01 2.329099e+02 +0 491 -1.467070e+03 7.600000e+01 +4 491 -1.755000e+02 2.334099e+02 +5 491 -9.617600e+02 3.696899e+02 +14 491 -2.432600e+02 1.882300e+02 +15 491 5.461600e+02 8.385999e+01 +16 491 -6.424200e+02 2.384200e+02 +19 491 1.508800e+02 1.055901e+02 +0 492 7.861899e+02 8.585999e+01 +4 492 1.029630e+03 2.722100e+02 +5 492 6.462500e+02 6.561000e+02 +0 493 -1.019070e+03 9.098999e+01 +4 493 3.767004e+01 2.482200e+02 +7 493 -8.509100e+02 2.536200e+02 +14 493 -5.973999e+01 1.918400e+02 +15 493 7.899301e+02 9.865002e+01 +16 493 -4.124700e+02 2.602100e+02 +0 494 -1.105750e+03 9.440002e+01 +4 494 -1.760010e+00 2.484800e+02 +7 494 -9.028600e+02 2.552800e+02 +14 494 -9.109000e+01 1.941200e+02 +15 494 7.461500e+02 9.928998e+01 +16 494 -4.527700e+02 2.595100e+02 +0 495 9.196299e+02 1.030400e+02 +4 495 1.126870e+03 2.911500e+02 +8 495 -7.295001e+01 9.172998e+01 +0 496 -1.337940e+03 1.033199e+02 +4 496 -7.679004e+01 2.489399e+02 +0 497 -1.466120e+03 1.052900e+02 +4 497 -1.757300e+02 2.487300e+02 +5 497 -9.656200e+02 3.902500e+02 +14 497 -2.430300e+02 2.015800e+02 +15 497 5.461700e+02 1.011500e+02 +16 497 -6.431100e+02 2.554200e+02 +19 497 1.508500e+02 1.338000e+02 +0 498 9.875200e+02 1.095699e+02 +4 498 1.173840e+03 3.009399e+02 +5 498 8.303899e+02 7.124900e+02 +8 498 3.613000e+01 9.833002e+01 +0 499 -1.464790e+03 1.218000e+02 +4 499 -1.758800e+02 2.571200e+02 +5 499 -9.680400e+02 4.014600e+02 +14 499 -2.431400e+02 2.092300e+02 +16 499 -6.440100e+02 2.649299e+02 +0 500 -1.082030e+03 1.252200e+02 +7 500 -8.876600e+02 2.802400e+02 +14 500 -8.139001e+01 2.087600e+02 +16 500 -4.421400e+02 2.774900e+02 +0 501 7.625801e+02 1.307500e+02 +2 501 -1.702800e+02 4.246002e+01 +5 501 6.208700e+02 6.885500e+02 +7 501 3.491100e+02 3.088800e+02 +9 501 -2.182400e+02 1.834500e+02 +11 501 4.195699e+02 1.228500e+02 +18 501 -4.089700e+02 -2.849976e+00 +20 501 -3.460300e+02 -2.001400e+02 +0 502 8.468999e+02 1.388600e+02 +7 502 3.874900e+02 3.183101e+02 +9 502 -1.906801e+02 2.004600e+02 +10 502 -1.392100e+02 -4.065000e+02 +11 502 4.446500e+02 1.372600e+02 +12 502 -7.402500e+02 -5.124700e+02 +13 502 -1.313160e+03 4.034000e+02 +18 502 -3.888199e+02 6.530029e+00 +20 502 -3.287800e+02 -1.922600e+02 +0 503 8.468999e+02 1.388600e+02 +7 503 3.874900e+02 3.183101e+02 +9 503 -1.906801e+02 2.004600e+02 +10 503 -1.392100e+02 -4.065000e+02 +11 503 4.446500e+02 1.372600e+02 +12 503 -7.402500e+02 -5.124700e+02 +13 503 -1.313160e+03 4.034000e+02 +18 503 -3.888199e+02 6.530029e+00 +20 503 -3.287800e+02 -1.922600e+02 +0 504 9.090400e+02 1.419000e+02 +4 504 1.115620e+03 3.147000e+02 +5 504 7.503300e+02 7.233201e+02 +8 504 -1.001200e+02 1.535900e+02 +0 505 9.309900e+02 1.441500e+02 +8 505 -6.302002e+01 1.559400e+02 +0 506 7.833101e+02 1.701699e+02 +5 506 6.354900e+02 7.221500e+02 +0 507 6.975801e+02 1.758000e+02 +4 507 9.741599e+02 3.198301e+02 +5 507 5.634700e+02 7.105400e+02 +0 508 9.813501e+02 1.930300e+02 +4 508 1.170980e+03 3.534700e+02 +16 508 6.287200e+02 3.751300e+02 +0 509 -1.198950e+03 2.132100e+02 +4 509 -4.687000e+01 3.075701e+02 +7 509 -9.651300e+02 3.446899e+02 +16 509 -5.014800e+02 3.221700e+02 +0 510 -1.234760e+03 2.145000e+02 +4 510 -6.455005e+01 3.079000e+02 +7 510 -9.898600e+02 3.452600e+02 +14 510 -1.402400e+02 2.503000e+02 +15 510 6.762600e+02 1.679100e+02 +16 510 -5.209500e+02 3.221100e+02 +0 511 8.999800e+02 2.217600e+02 +4 511 1.110690e+03 3.622300e+02 +5 511 7.347700e+02 7.844100e+02 +0 512 6.032400e+02 2.375701e+02 +2 512 -2.566100e+02 1.632400e+02 +9 512 -2.968300e+02 2.659800e+02 +0 513 6.032400e+02 2.375701e+02 +2 513 -2.573000e+02 1.578700e+02 +4 513 9.163101e+02 3.491799e+02 +5 513 4.799399e+02 7.402200e+02 +7 513 2.669900e+02 3.769099e+02 +9 513 -2.984900e+02 2.631500e+02 +10 513 -2.248600e+02 -3.550200e+02 +11 513 3.496100e+02 1.968100e+02 +12 513 -8.448800e+02 -4.633199e+02 +18 513 -4.586300e+02 4.758997e+01 +0 514 5.644900e+02 2.563301e+02 +4 514 8.932100e+02 3.594500e+02 +0 515 6.849199e+02 2.691100e+02 +4 515 9.681699e+02 3.738000e+02 +5 515 5.448199e+02 7.815300e+02 +0 516 1.472140e+03 2.822700e+02 +8 516 6.974500e+02 3.661200e+02 +0 517 -1.530210e+03 2.855701e+02 +4 517 -2.118600e+02 3.390801e+02 +14 517 -2.750300e+02 2.838000e+02 +15 517 5.048101e+02 2.021200e+02 +16 517 -6.882700e+02 3.547300e+02 +0 518 5.487000e+02 3.426100e+02 +5 518 4.266500e+02 8.153600e+02 +8 518 -7.274800e+02 4.981899e+02 +0 519 -1.293480e+03 3.512200e+02 +4 519 -9.575000e+01 3.770601e+02 +19 519 3.041300e+02 3.791200e+02 +0 520 -1.554800e+03 3.521000e+02 +4 520 -2.266300e+02 3.739800e+02 +5 520 -1.066470e+03 5.524100e+02 +14 520 -2.891600e+02 3.167800e+02 +16 520 -7.097300e+02 3.932000e+02 +19 520 5.517004e+01 3.674199e+02 +0 521 -1.411580e+03 3.537800e+02 +4 521 -1.543199e+02 3.763401e+02 +5 521 -9.679900e+02 5.716700e+02 +15 521 5.735000e+02 2.459400e+02 +16 521 -6.248900e+02 3.966500e+02 +19 521 1.930400e+02 3.761799e+02 +0 522 6.297000e+02 3.720901e+02 +5 522 4.887500e+02 8.512300e+02 +0 523 -8.025200e+02 3.789000e+02 +4 523 1.311200e+02 4.106799e+02 +7 523 -7.443500e+02 4.929900e+02 +15 523 8.918900e+02 2.857200e+02 +16 523 -3.278200e+02 4.344500e+02 +19 523 7.196101e+02 4.341200e+02 +0 524 5.832100e+02 3.905901e+02 +5 524 4.493400e+02 8.567900e+02 +0 525 -8.919700e+02 4.238600e+02 +4 525 9.200000e+01 4.291799e+02 +7 525 -7.836800e+02 5.187200e+02 +14 525 -1.416000e+01 3.441400e+02 +15 525 8.521600e+02 3.058700e+02 +16 525 -3.640900e+02 4.538300e+02 +19 525 6.537900e+02 4.697300e+02 +0 526 -8.004100e+02 4.382400e+02 +4 526 1.315500e+02 4.418101e+02 +15 526 8.919500e+02 3.193201e+02 +16 526 -3.288700e+02 4.659600e+02 +19 526 7.212800e+02 4.856699e+02 +0 527 -1.354780e+03 4.545901e+02 +4 527 -1.281100e+02 4.293900e+02 +5 527 -9.441400e+02 6.506000e+02 +14 527 -1.944700e+02 3.628700e+02 +15 527 6.034800e+02 3.060800e+02 +16 527 -5.970500e+02 4.548201e+02 +19 527 2.421700e+02 4.779399e+02 +0 528 -1.610030e+03 4.679700e+02 +4 528 -2.606801e+02 4.335500e+02 +15 528 4.484200e+02 3.094800e+02 +16 528 -7.531700e+02 4.600701e+02 +19 528 -5.160034e+00 4.756599e+02 +0 529 -2.273600e+02 4.729399e+02 +7 529 6.239600e+02 2.494800e+02 +9 529 5.278601e+02 9.109985e+00 +10 529 3.570400e+02 -4.614399e+02 +12 529 -3.732800e+02 -6.723101e+02 +13 529 1.040680e+03 2.365500e+02 +16 529 5.287500e+02 2.814200e+02 +17 529 2.232800e+02 2.581000e+02 +18 529 2.356006e+01 -1.211300e+02 +0 530 -1.366230e+03 4.720000e+02 +4 530 -1.332500e+02 4.381300e+02 +5 530 -9.541200e+02 6.613600e+02 +7 530 -1.099180e+03 5.495200e+02 +14 530 -1.984300e+02 3.709200e+02 +16 530 -6.027900e+02 4.651300e+02 +19 530 2.325300e+02 4.944299e+02 +0 531 -1.249580e+03 4.815100e+02 +4 531 -7.756995e+01 4.454600e+02 +5 531 -8.781200e+02 6.834900e+02 +7 531 -1.015060e+03 5.564500e+02 +14 531 -1.500300e+02 3.742000e+02 +15 531 6.616400e+02 3.244600e+02 +16 531 -5.412800e+02 4.732400e+02 +19 531 3.376600e+02 5.090801e+02 +20 531 -1.276320e+03 -2.620996e+01 +0 532 -1.355830e+03 4.867900e+02 +4 532 -1.289200e+02 4.453800e+02 +5 532 -9.493600e+02 6.733101e+02 +7 532 -1.094850e+03 5.617000e+02 +10 532 -1.479820e+03 -1.531300e+02 +15 532 6.033300e+02 3.240400e+02 +16 532 -5.994100e+02 4.737600e+02 +19 532 2.403800e+02 5.090500e+02 +0 533 -8.520300e+02 5.002800e+02 +7 533 -7.719400e+02 5.843300e+02 +10 533 -1.175870e+03 -1.418400e+02 +14 533 -4.279999e+00 3.800000e+02 +19 533 6.776399e+02 5.506699e+02 +0 534 5.270701e+02 5.125100e+02 +5 534 3.965800e+02 9.484301e+02 +0 535 -8.178600e+02 5.227200e+02 +4 535 1.219000e+02 4.875100e+02 +7 535 -7.545100e+02 6.025300e+02 +14 535 6.829987e+00 3.883900e+02 +15 535 8.831500e+02 3.714600e+02 +19 535 7.068201e+02 5.737600e+02 +0 536 -1.700200e+03 5.917600e+02 +4 536 -3.097400e+02 4.971100e+02 +5 536 -1.209770e+03 7.061500e+02 +15 536 3.931400e+02 3.790900e+02 +16 536 -8.161600e+02 5.316000e+02 +19 536 -9.587000e+01 5.882100e+02 +0 537 -1.070490e+03 6.353201e+02 +4 537 5.930054e+00 5.328101e+02 +0 538 -5.407900e+02 6.398201e+02 +7 538 4.733600e+02 3.268000e+02 +13 538 4.079900e+02 5.654600e+02 +0 539 -9.264100e+02 6.508700e+02 +4 539 7.143994e+01 5.507900e+02 +7 539 -8.125400e+02 7.006300e+02 +16 539 -3.893300e+02 5.844299e+02 +19 539 6.139200e+02 6.988900e+02 +0 540 -8.819300e+02 6.721100e+02 +4 540 9.297998e+01 5.638600e+02 +7 540 -7.848800e+02 7.170800e+02 +10 540 -1.177320e+03 -1.965002e+01 +14 540 -1.016000e+01 4.589100e+02 +15 540 8.522700e+02 4.590701e+02 +18 540 -1.301760e+03 3.398201e+02 +19 540 6.529900e+02 7.215200e+02 +0 541 -8.819300e+02 6.721100e+02 +7 541 -7.848800e+02 7.170800e+02 +15 541 8.522700e+02 4.590701e+02 +19 541 6.529900e+02 7.215200e+02 +0 542 -9.029000e+02 7.617200e+02 +4 542 7.997998e+01 6.113101e+02 +5 542 -6.878800e+02 9.411700e+02 +15 542 8.388101e+02 5.136600e+02 +16 542 -3.831100e+02 6.497600e+02 +19 542 6.263401e+02 8.109100e+02 +0 543 -1.554080e+03 7.832000e+02 +4 543 -2.398900e+02 5.990200e+02 +5 543 -1.140170e+03 8.636200e+02 +10 543 -1.646350e+03 9.103003e+01 +14 543 -2.947200e+02 5.196700e+02 +15 543 4.753700e+02 4.933600e+02 +16 543 -7.329300e+02 6.455500e+02 +19 543 3.616003e+01 7.818700e+02 +0 544 7.408000e+02 -6.196997e+01 +4 544 9.978000e+02 1.850701e+02 +0 545 1.319310e+03 -2.392004e+01 +8 545 -3.551900e+02 1.334998e+01 +0 546 -1.371750e+03 1.091003e+01 +7 546 -1.086260e+03 1.847400e+02 +10 546 -1.503760e+03 -5.227000e+02 +16 546 -5.864100e+02 2.048400e+02 +0 547 7.169399e+02 7.869995e+01 +5 547 5.895601e+02 6.425000e+02 +6 547 -2.989000e+02 -6.153998e+01 +0 548 8.632700e+02 9.995996e+01 +4 548 1.082040e+03 2.863800e+02 +5 548 7.131000e+02 6.824200e+02 +0 549 7.016299e+02 1.014100e+02 +4 549 9.758000e+02 2.782300e+02 +5 549 5.742400e+02 6.577000e+02 +6 549 -3.185800e+02 -2.551001e+01 +0 550 7.016299e+02 1.014100e+02 +4 550 9.758000e+02 2.782300e+02 +5 550 5.742400e+02 6.577000e+02 +0 551 8.340400e+02 1.051000e+02 +5 551 6.873600e+02 6.812800e+02 +6 551 -1.402400e+02 -4.740997e+01 +0 552 6.997500e+02 1.186600e+02 +4 552 9.747900e+02 2.879399e+02 +0 553 6.997500e+02 1.186600e+02 +4 553 9.747900e+02 2.879399e+02 +0 554 1.613570e+03 1.226100e+02 +7 554 9.325901e+02 2.860200e+02 +8 554 8.835000e+02 1.279500e+02 +17 554 -8.937300e+02 3.359600e+02 +20 554 4.983997e+01 -2.217100e+02 +0 555 9.993401e+02 1.233800e+02 +4 555 1.184490e+03 3.115200e+02 +5 555 8.404500e+02 7.277300e+02 +8 555 5.553003e+01 1.206800e+02 +16 555 6.380300e+02 3.360500e+02 +0 556 9.788000e+02 1.299099e+02 +4 556 1.166490e+03 3.134099e+02 +8 556 1.810999e+01 1.299300e+02 +16 556 6.294301e+02 3.372700e+02 +0 557 9.788000e+02 1.299099e+02 +4 557 1.166490e+03 3.134099e+02 +8 557 1.810999e+01 1.299300e+02 +16 557 6.294301e+02 3.372700e+02 +0 558 9.469399e+02 1.378800e+02 +4 558 1.142930e+03 3.158700e+02 +8 558 -3.504999e+01 1.450700e+02 +0 559 6.270100e+02 1.526699e+02 +2 559 -2.490400e+02 6.304999e+01 +3 559 -7.954200e+02 2.301699e+02 +4 559 9.300100e+02 3.035901e+02 +5 559 5.084399e+02 6.832400e+02 +7 559 2.778700e+02 3.183900e+02 +9 559 -2.881000e+02 1.905300e+02 +10 559 -2.178600e+02 -4.059000e+02 +11 559 3.570200e+02 1.284300e+02 +12 559 -8.365900e+02 -5.187300e+02 +13 559 -1.662030e+03 4.279299e+02 +20 559 -3.842900e+02 -1.970900e+02 +0 560 -1.698270e+03 2.016200e+02 +4 560 -2.999000e+02 2.963201e+02 +19 560 -8.006995e+01 2.184800e+02 +0 561 -1.530230e+03 2.059800e+02 +4 561 -2.080400e+02 2.986899e+02 +14 561 -2.718700e+02 2.485900e+02 +0 562 -9.171900e+02 2.068301e+02 +4 562 8.401001e+01 3.119700e+02 +7 562 -7.901400e+02 3.476200e+02 +10 562 -1.204280e+03 -3.665699e+02 +14 562 -2.166000e+01 2.448400e+02 +15 562 8.429700e+02 1.718900e+02 +16 562 -3.676000e+02 3.287300e+02 +19 562 6.417600e+02 2.504900e+02 +0 563 -1.498570e+03 2.065400e+02 +4 563 -1.929900e+02 2.991899e+02 +5 563 -1.002290e+03 4.566799e+02 +14 563 -2.565200e+02 2.484000e+02 +16 563 -6.641800e+02 3.106700e+02 +19 563 1.192600e+02 2.304800e+02 +0 564 5.689299e+02 2.128800e+02 +2 564 -2.784000e+02 1.315200e+02 +3 564 -8.860400e+02 3.812000e+02 +4 564 8.954199e+02 3.354199e+02 +7 564 2.494100e+02 3.594500e+02 +9 564 -3.155800e+02 2.398401e+02 +10 564 -2.379600e+02 -3.691899e+02 +11 564 3.338500e+02 1.763500e+02 +12 564 -8.611000e+02 -4.792500e+02 +18 564 -4.700000e+02 3.325000e+01 +20 564 -3.982400e+02 -1.702400e+02 +0 565 7.149199e+02 2.170300e+02 +3 565 -6.608100e+02 3.283201e+02 +4 565 9.855901e+02 3.461000e+02 +5 565 5.744700e+02 7.467800e+02 +0 566 -1.036100e+03 2.192500e+02 +4 566 2.880005e+01 3.147400e+02 +15 566 7.815400e+02 1.754600e+02 +0 567 -1.076070e+03 2.214199e+02 +4 567 9.819946e+00 3.146200e+02 +15 567 7.603000e+02 1.754400e+02 +16 567 -4.428000e+02 3.309800e+02 +0 568 -8.621300e+02 2.240601e+02 +7 568 -7.677100e+02 3.595400e+02 +10 568 -1.185480e+03 -3.557900e+02 +14 568 -7.640015e+00 2.499400e+02 +15 568 8.664500e+02 1.823500e+02 +19 568 6.810901e+02 2.644900e+02 +0 569 9.450200e+02 2.265100e+02 +4 569 1.144190e+03 3.706000e+02 +5 569 7.772900e+02 7.987000e+02 +8 569 -3.601001e+01 2.796200e+02 +16 569 6.131200e+02 3.899399e+02 +0 570 -1.193820e+03 2.292600e+02 +4 570 -4.508997e+01 3.157400e+02 +7 570 -9.641500e+02 3.578500e+02 +15 570 6.976700e+02 1.770600e+02 +16 570 -5.010300e+02 3.316500e+02 +0 571 -1.237450e+03 2.304299e+02 +4 571 -6.653003e+01 3.153101e+02 +5 571 -8.305600e+02 5.059600e+02 +0 572 -1.385760e+03 2.361100e+02 +4 572 -1.375400e+02 3.154800e+02 +0 573 -1.539910e+03 2.378000e+02 +4 573 -2.150300e+02 3.144500e+02 +5 573 -1.036730e+03 4.731600e+02 +14 573 -2.776300e+02 2.629600e+02 +15 573 5.013900e+02 1.762500e+02 +16 573 -6.912000e+02 3.275500e+02 +19 573 7.776001e+01 2.591400e+02 +0 574 5.725100e+02 2.384900e+02 +2 574 -2.780800e+02 1.615200e+02 +7 574 2.509900e+02 3.768900e+02 +9 574 -3.152300e+02 2.619000e+02 +11 574 3.340200e+02 1.981000e+02 +12 574 -8.599800e+02 -4.615000e+02 +0 575 -1.483040e+03 2.391200e+02 +4 575 -1.854900e+02 3.156500e+02 +14 575 -2.498600e+02 2.634700e+02 +15 575 5.362400e+02 1.774100e+02 +16 575 -6.571800e+02 3.295000e+02 +19 575 1.327000e+02 2.627300e+02 +0 576 6.322600e+02 2.441400e+02 +4 576 9.340701e+02 3.567200e+02 +5 576 5.036300e+02 7.531600e+02 +0 577 6.644399e+02 2.562200e+02 +5 577 5.275200e+02 7.684299e+02 +0 578 6.504600e+02 2.563700e+02 +4 578 9.454199e+02 3.648000e+02 +5 578 5.174301e+02 7.665400e+02 +6 578 -3.778600e+02 1.979700e+02 +7 578 2.908600e+02 3.931799e+02 +9 578 -2.768800e+02 2.854000e+02 +12 578 -8.222000e+02 -4.424399e+02 +18 578 -4.443199e+02 6.059009e+01 +20 578 -3.759800e+02 -1.447100e+02 +0 579 -1.460120e+03 2.685901e+02 +4 579 -1.766100e+02 3.322600e+02 +16 579 -6.479100e+02 3.478500e+02 +0 580 6.570901e+02 2.727100e+02 +4 580 9.498999e+02 3.743900e+02 +5 580 5.202100e+02 7.795701e+02 +7 580 2.952900e+02 4.041000e+02 +9 580 -2.656801e+02 3.010400e+02 +10 580 -2.037500e+02 -3.291801e+02 +11 580 3.741700e+02 2.343900e+02 +12 580 -8.176100e+02 -4.325500e+02 +13 580 -1.593540e+03 7.737000e+02 +18 580 -4.412100e+02 6.935999e+01 +0 581 5.604399e+02 2.767400e+02 +4 581 8.912900e+02 3.712500e+02 +0 582 6.704900e+02 2.854600e+02 +4 582 9.580300e+02 3.834500e+02 +5 582 5.298800e+02 7.930601e+02 +0 583 5.924199e+02 2.906699e+02 +5 583 4.670200e+02 7.819900e+02 +0 584 8.373201e+02 2.968600e+02 +8 584 -2.221200e+02 3.990500e+02 +0 585 -8.134800e+02 2.983600e+02 +7 585 -7.986000e+02 4.336699e+02 +0 586 7.520701e+02 3.344299e+02 +5 586 6.036200e+02 8.526200e+02 +0 587 -1.190510e+03 3.448101e+02 +7 587 -9.648000e+02 4.483700e+02 +14 587 -1.232800e+02 3.101800e+02 +15 587 6.996700e+02 2.457000e+02 +16 587 -5.031100e+02 3.970200e+02 +0 588 -1.580980e+03 3.504000e+02 +4 588 -2.412500e+02 3.731599e+02 +5 588 -1.085400e+03 5.482700e+02 +15 588 4.713101e+02 2.419900e+02 +19 588 2.902002e+01 3.649900e+02 +0 589 -1.374500e+03 3.537800e+02 +4 589 -1.341200e+02 3.766300e+02 +7 589 -1.097750e+03 4.541300e+02 +14 589 -2.005600e+02 3.157900e+02 +15 589 5.969900e+02 2.461600e+02 +16 589 -6.012700e+02 3.972600e+02 +19 589 2.319000e+02 3.781699e+02 +0 590 -1.434390e+03 3.526100e+02 +4 590 -1.659399e+02 3.751300e+02 +14 590 -2.299400e+02 3.158400e+02 +15 590 5.606600e+02 2.449500e+02 +16 590 -6.357600e+02 3.956200e+02 +19 590 1.718800e+02 3.743201e+02 +0 591 -1.436430e+03 3.663700e+02 +4 591 -1.669600e+02 3.821300e+02 +14 591 -2.314300e+02 3.221400e+02 +15 591 5.584500e+02 2.524600e+02 +16 591 -6.386200e+02 4.033300e+02 +19 591 1.691400e+02 3.874199e+02 +0 592 -1.479700e+03 3.713000e+02 +4 592 -1.867800e+02 3.834000e+02 +14 592 -2.486900e+02 3.244400e+02 +15 592 5.362900e+02 2.538100e+02 +16 592 -6.606900e+02 4.048900e+02 +19 592 1.316700e+02 3.901899e+02 +0 593 5.185701e+02 3.724000e+02 +4 593 8.666299e+02 4.237900e+02 +0 594 -7.697500e+02 3.742600e+02 +4 594 1.443700e+02 4.115300e+02 +15 594 9.041000e+02 2.855100e+02 +16 594 -3.170400e+02 4.348500e+02 +19 594 7.423501e+02 4.265400e+02 +0 595 -1.235250e+03 4.512300e+02 +7 595 -1.003180e+03 5.326899e+02 +14 595 -1.429900e+02 3.596200e+02 +16 595 -5.323300e+02 4.567200e+02 +19 595 3.519900e+02 4.803101e+02 +0 596 5.383601e+02 4.530500e+02 +4 596 8.801499e+02 4.717000e+02 +5 596 4.072600e+02 8.979301e+02 +0 597 -1.314930e+03 4.842300e+02 +4 597 -1.090300e+02 4.451599e+02 +5 597 -9.231200e+02 6.767800e+02 +14 597 -1.772300e+02 3.759600e+02 +15 597 6.269399e+02 3.233900e+02 +16 597 -5.756400e+02 4.730300e+02 +19 597 2.796700e+02 5.078600e+02 +0 598 -1.552600e+03 4.830100e+02 +4 598 -2.310200e+02 4.412200e+02 +5 598 -1.086420e+03 6.465900e+02 +14 598 -2.906500e+02 3.778300e+02 +15 598 4.834399e+02 3.180300e+02 +16 598 -7.167600e+02 4.693500e+02 +19 598 4.918994e+01 4.932400e+02 +0 599 -1.181180e+03 4.894500e+02 +4 599 -4.498999e+01 4.518900e+02 +7 599 -9.657500e+02 5.636700e+02 +10 599 -1.353870e+03 -1.554000e+02 +14 599 -1.211800e+02 3.770700e+02 +15 599 6.998101e+02 3.316600e+02 +16 599 -5.058300e+02 4.802800e+02 +19 599 3.991200e+02 5.214199e+02 +20 599 -1.240770e+03 -2.144000e+01 +0 600 -1.181180e+03 4.894500e+02 +4 600 -4.498999e+01 4.518900e+02 +19 600 3.991200e+02 5.214199e+02 +20 600 -1.240770e+03 -2.144000e+01 +0 601 -1.203410e+03 5.617800e+02 +4 601 -5.643005e+01 4.890200e+02 +7 601 -9.834700e+02 6.206700e+02 +14 601 -1.297000e+02 4.107800e+02 +15 601 6.864700e+02 3.736600e+02 +16 601 -5.196800e+02 5.208000e+02 +19 601 3.774200e+02 5.909399e+02 +0 602 -8.166900e+02 6.215500e+02 +4 602 1.209399e+02 5.428101e+02 +0 603 -9.285600e+02 6.241000e+02 +5 603 -6.824300e+02 8.345500e+02 +7 603 -8.127900e+02 6.775100e+02 +10 603 -1.204690e+03 -5.435999e+01 +14 603 -2.698001e+01 4.368600e+02 +16 603 -3.885500e+02 5.680601e+02 +18 603 -1.324900e+03 3.059600e+02 +0 604 -8.693000e+02 6.257700e+02 +4 604 9.753003e+01 5.394399e+02 +15 604 8.576300e+02 4.331799e+02 +16 604 -3.644400e+02 5.716100e+02 +19 604 6.605801e+02 6.768500e+02 +0 605 -8.693000e+02 6.257700e+02 +4 605 9.753003e+01 5.394399e+02 +5 605 -6.438100e+02 8.444200e+02 +7 605 -7.836400e+02 6.811600e+02 +10 605 -1.181370e+03 -5.475000e+01 +14 605 -9.380005e+00 4.364700e+02 +16 605 -3.644400e+02 5.716100e+02 +19 605 6.605801e+02 6.768500e+02 +0 606 -1.410870e+03 7.767900e+02 +4 606 -1.650200e+02 5.970800e+02 +5 606 -1.036540e+03 8.769600e+02 +10 606 -1.518440e+03 7.237000e+01 +14 606 -2.237400e+02 5.144200e+02 +15 606 5.620900e+02 4.928800e+02 +19 606 1.742300e+02 7.872800e+02 +20 606 -1.371490e+03 1.530901e+02 +0 607 -1.700100e+03 7.771100e+02 +4 607 -3.146700e+02 5.940000e+02 +5 607 -1.241350e+03 8.412900e+02 +15 607 3.879900e+02 4.853201e+02 +19 607 -1.011600e+02 7.646899e+02 +0 608 -1.237250e+03 7.796600e+02 +4 608 -7.772998e+01 6.038101e+02 +14 608 -1.458300e+02 5.133800e+02 +0 609 -1.336020e+03 7.891300e+02 +4 609 -1.291100e+02 6.051000e+02 +0 610 -1.493610e+03 8.428300e+02 +4 610 -2.099700e+02 6.308900e+02 +5 610 -1.106570e+03 9.149301e+02 +14 610 -2.651900e+02 5.474000e+02 +15 610 5.094301e+02 5.294000e+02 +19 610 9.106006e+01 8.444500e+02 +20 610 -1.430840e+03 1.996200e+02 +0 611 -1.493610e+03 8.428300e+02 +4 611 -2.099700e+02 6.308900e+02 +5 611 -1.106570e+03 9.149301e+02 +14 611 -2.651900e+02 5.474000e+02 +15 611 5.094301e+02 5.294000e+02 +20 611 -1.430840e+03 1.996200e+02 +0 612 -1.084230e+03 8.818500e+02 +4 612 -2.322998e+01 6.760701e+02 +16 612 -5.005300e+02 7.205300e+02 +0 613 -1.443860e+03 8.871300e+02 +4 613 -1.855000e+02 6.549500e+02 +14 613 -2.413400e+02 5.678199e+02 +15 613 5.382500e+02 5.571700e+02 +0 614 7.312200e+02 -2.409998e+01 +4 614 9.931201e+02 2.071300e+02 +0 615 -1.197160e+03 -4.310059e+00 +4 615 -4.395996e+01 1.960400e+02 +0 616 7.244600e+02 6.469995e+01 +4 616 9.893000e+02 2.577700e+02 +6 616 -2.900800e+02 -8.132001e+01 +0 617 8.241001e+02 9.471997e+01 +4 617 1.056480e+03 2.808000e+02 +5 617 6.801400e+02 6.717300e+02 +0 618 9.024500e+02 9.635999e+01 +5 618 7.482100e+02 6.861700e+02 +8 618 -1.134300e+02 8.335999e+01 +0 619 8.823501e+02 9.703003e+01 +4 619 1.096010e+03 2.856500e+02 +5 619 7.315300e+02 6.833900e+02 +7 619 4.024600e+02 2.920400e+02 +0 620 8.823501e+02 9.703003e+01 +2 620 -1.350100e+02 1.608002e+01 +4 620 1.096010e+03 2.856500e+02 +5 620 7.315300e+02 6.833900e+02 +6 620 -8.096002e+01 -6.742999e+01 +7 620 3.982300e+02 2.922400e+02 +8 620 -1.447600e+02 8.465997e+01 +10 620 -1.308000e+02 -4.301100e+02 +11 620 4.528400e+02 1.085900e+02 +12 620 -7.299300e+02 -5.368500e+02 +13 620 -1.277950e+03 2.940901e+02 +18 620 -3.819100e+02 -1.218005e+01 +20 620 -3.231300e+02 -2.082000e+02 +0 621 6.581799e+02 9.806995e+01 +4 621 9.486001e+02 2.740901e+02 +5 621 5.384700e+02 6.476400e+02 +6 621 -3.817700e+02 -2.242999e+01 +0 622 9.442500e+02 1.025601e+02 +4 622 1.141550e+03 2.927000e+02 +8 622 -3.697998e+01 8.790002e+01 +16 622 6.115400e+02 3.197600e+02 +0 623 6.663899e+02 1.061300e+02 +5 623 5.449900e+02 6.555701e+02 +6 623 -3.684500e+02 -1.376001e+01 +0 624 1.005480e+03 1.098199e+02 +8 624 6.483997e+01 9.696002e+01 +0 625 9.293799e+02 1.149301e+02 +4 625 1.129250e+03 2.991599e+02 +0 626 7.324900e+02 1.149600e+02 +4 626 9.954600e+02 2.878000e+02 +0 627 9.682100e+02 1.198199e+02 +4 627 1.159210e+03 3.054600e+02 +8 627 1.229980e+00 1.146800e+02 +0 628 6.658701e+02 1.234100e+02 +4 628 9.535500e+02 2.897500e+02 +0 629 1.647050e+03 1.297600e+02 +7 629 9.518799e+02 2.905901e+02 +8 629 9.310200e+02 1.374200e+02 +17 629 -8.434200e+02 3.470100e+02 +0 630 5.506699e+02 1.423500e+02 +2 630 -2.894000e+02 4.337000e+01 +3 630 -9.180200e+02 2.221799e+02 +4 630 8.841599e+02 2.949900e+02 +7 630 2.395900e+02 3.069399e+02 +9 630 -3.240300e+02 1.728600e+02 +10 630 -2.452900e+02 -4.167100e+02 +11 630 3.255699e+02 1.111800e+02 +12 630 -8.716500e+02 -5.324399e+02 +18 630 -4.767700e+02 -8.380005e+00 +20 630 -4.041000e+02 -2.063800e+02 +0 631 7.310901e+02 1.568301e+02 +5 631 5.941400e+02 7.029500e+02 +0 632 7.310901e+02 1.568301e+02 +4 632 9.953000e+02 3.124700e+02 +5 632 5.941400e+02 7.029500e+02 +0 633 7.318301e+02 1.727200e+02 +5 633 5.921400e+02 7.159600e+02 +0 634 8.566499e+02 1.771000e+02 +4 634 1.079450e+03 3.317600e+02 +5 634 7.001600e+02 7.411500e+02 +0 635 9.475701e+02 1.800701e+02 +5 635 7.843501e+02 7.602800e+02 +8 635 -3.285999e+01 2.078500e+02 +16 635 6.125900e+02 3.649600e+02 +0 636 9.475701e+02 1.800701e+02 +4 636 1.144660e+03 3.402100e+02 +5 636 7.843501e+02 7.602800e+02 +8 636 -3.285999e+01 2.078500e+02 +16 636 6.125900e+02 3.649600e+02 +0 637 8.446799e+02 1.822400e+02 +4 637 1.070820e+03 3.338000e+02 +5 637 6.886000e+02 7.426200e+02 +0 638 6.648101e+02 1.836100e+02 +4 638 9.536299e+02 3.238000e+02 +5 638 5.353101e+02 7.122000e+02 +6 638 -3.636000e+02 9.378003e+01 +0 639 6.648101e+02 1.836100e+02 +4 639 9.536299e+02 3.238000e+02 +0 640 8.653101e+02 1.893600e+02 +4 640 1.084880e+03 3.389399e+02 +5 640 7.055699e+02 7.509100e+02 +0 641 -1.208780e+03 1.920400e+02 +7 641 -9.727900e+02 3.281100e+02 +14 641 -1.311500e+02 2.398400e+02 +15 641 6.900800e+02 1.547300e+02 +16 641 -5.071000e+02 3.106500e+02 +0 642 -1.223330e+03 1.923600e+02 +5 642 -8.146000e+02 4.815701e+02 +0 643 9.603799e+02 2.010500e+02 +5 643 7.961101e+02 7.784700e+02 +8 643 -8.210022e+00 2.365300e+02 +0 644 9.603799e+02 2.010500e+02 +4 644 1.155460e+03 3.549399e+02 +5 644 7.961101e+02 7.784700e+02 +8 644 -8.210022e+00 2.365300e+02 +0 645 7.251101e+02 2.045901e+02 +4 645 9.907800e+02 3.391599e+02 +5 645 5.826600e+02 7.382900e+02 +0 646 -9.362300e+02 2.093900e+02 +4 646 7.562000e+01 3.131100e+02 +7 646 -8.028300e+02 3.493101e+02 +14 646 -2.922000e+01 2.458100e+02 +15 646 8.328700e+02 1.731000e+02 +16 646 -3.768000e+02 3.299000e+02 +19 646 6.248799e+02 2.526799e+02 +0 647 -8.711700e+02 2.118000e+02 +4 647 1.038500e+02 3.170000e+02 +7 647 -7.714100e+02 3.538700e+02 +10 647 -1.188730e+03 -3.615699e+02 +14 647 -9.899994e+00 2.468600e+02 +16 647 -3.505900e+02 3.339800e+02 +0 648 7.974099e+02 2.152700e+02 +4 648 1.038600e+03 3.501599e+02 +0 649 6.696101e+02 2.165100e+02 +4 649 9.578000e+02 3.429199e+02 +7 649 2.979900e+02 3.671200e+02 +9 649 -2.698700e+02 2.557900e+02 +10 649 -2.030200e+02 -3.649600e+02 +11 649 3.738800e+02 1.929500e+02 +12 649 -8.179600e+02 -4.680400e+02 +13 649 -1.595290e+03 6.116699e+02 +18 649 -4.403199e+02 4.240002e+01 +20 649 -3.730900e+02 -1.617300e+02 +0 650 -1.132450e+03 2.268000e+02 +4 650 -1.616003e+01 3.160601e+02 +14 650 -1.002900e+02 2.552500e+02 +15 650 7.311400e+02 1.767900e+02 +19 650 4.540400e+02 2.628301e+02 +0 651 -1.360890e+03 2.340300e+02 +4 651 -1.262000e+02 3.150400e+02 +5 651 -9.141400e+02 4.929299e+02 +14 651 -1.960800e+02 2.601600e+02 +15 651 6.051500e+02 1.760900e+02 +16 651 -5.910400e+02 3.298101e+02 +19 651 2.449900e+02 2.617200e+02 +0 652 8.003501e+02 2.360200e+02 +4 652 1.041490e+03 3.626599e+02 +5 652 6.445800e+02 7.753700e+02 +6 652 -1.742100e+02 1.324000e+02 +0 653 8.102300e+02 2.422600e+02 +4 653 1.048160e+03 3.660601e+02 +6 653 -1.605400e+02 1.363400e+02 +0 654 -1.311180e+03 2.457000e+02 +4 654 -1.025699e+02 3.223600e+02 +7 654 -1.050540e+03 3.695300e+02 +19 654 2.900300e+02 2.756699e+02 +0 655 5.965701e+02 2.521699e+02 +2 655 -2.583400e+02 1.762900e+02 +5 655 4.727800e+02 7.537800e+02 +7 655 2.653199e+02 3.865300e+02 +9 655 -2.990699e+02 2.763301e+02 +10 655 -2.250200e+02 -3.444301e+02 +11 655 3.500900e+02 2.107900e+02 +13 655 -1.693790e+03 7.109000e+02 +18 655 -4.595500e+02 5.458008e+01 +0 656 1.497830e+03 2.574299e+02 +8 656 7.324700e+02 3.294600e+02 +0 657 7.771799e+02 2.578800e+02 +5 657 6.215400e+02 7.884900e+02 +0 658 7.620901e+02 2.573700e+02 +2 658 -1.737200e+02 1.930800e+02 +4 658 1.016450e+03 3.728301e+02 +10 658 -1.653600e+02 -3.334100e+02 +0 659 5.103301e+02 2.563600e+02 +5 659 4.064600e+02 7.439900e+02 +0 660 5.103301e+02 2.563600e+02 +5 660 4.064600e+02 7.439900e+02 +0 661 6.877900e+02 2.657900e+02 +4 661 9.697000e+02 3.713101e+02 +0 662 8.075000e+02 2.668900e+02 +5 662 6.461200e+02 8.027600e+02 +0 663 5.506299e+02 2.968201e+02 +5 663 4.328600e+02 7.799600e+02 +0 664 6.056699e+02 2.984399e+02 +4 664 9.199800e+02 3.860000e+02 +5 664 4.782400e+02 7.904000e+02 +0 665 5.904299e+02 3.040100e+02 +4 665 9.095601e+02 3.879099e+02 +8 665 -6.550300e+02 4.333500e+02 +0 666 -7.983900e+02 3.070701e+02 +7 666 -7.884700e+02 4.417200e+02 +0 667 6.236899e+02 3.169700e+02 +4 667 9.299800e+02 3.987300e+02 +5 667 4.890000e+02 8.092700e+02 +0 668 -8.786800e+02 3.215500e+02 +4 668 9.862000e+01 3.749900e+02 +7 668 -7.781900e+02 4.394199e+02 +15 668 8.589100e+02 2.432700e+02 +19 668 6.670100e+02 3.665400e+02 +0 669 -9.160600e+02 3.281699e+02 +4 669 8.247998e+01 3.763000e+02 +15 669 8.412200e+02 2.456400e+02 +19 669 6.365400e+02 3.725000e+02 +0 670 -1.580620e+03 3.303101e+02 +4 670 -2.412000e+02 3.644000e+02 +5 670 -1.082250e+03 5.332700e+02 +19 670 2.791003e+01 3.454700e+02 +0 671 1.506460e+03 3.398600e+02 +8 671 7.408600e+02 4.554900e+02 +0 672 -1.033070e+03 3.437300e+02 +4 672 2.812000e+01 3.800901e+02 +14 672 -6.320001e+01 3.080400e+02 +15 672 7.813199e+02 2.501500e+02 +19 672 5.363199e+02 3.833101e+02 +0 673 -1.069300e+03 3.473500e+02 +4 673 1.098999e+01 3.807800e+02 +7 673 -8.867300e+02 4.526500e+02 +14 673 -7.698001e+01 3.102700e+02 +15 673 7.619900e+02 2.509500e+02 +16 673 -4.439600e+02 4.024500e+02 +19 673 5.048300e+02 3.852500e+02 +20 673 -1.190640e+03 -1.018101e+02 +0 674 -7.522000e+02 3.515901e+02 +7 674 -8.099500e+02 4.931500e+02 +0 675 5.350400e+02 3.540701e+02 +5 675 4.148300e+02 8.218101e+02 +8 675 -7.512900e+02 5.166300e+02 +0 676 -1.051880e+03 3.536000e+02 +7 676 -8.747400e+02 4.578700e+02 +15 676 7.730400e+02 2.550500e+02 +18 676 -1.372970e+03 1.187200e+02 +0 677 -1.138220e+03 3.527500e+02 +4 677 -2.170996e+01 3.812500e+02 +19 677 4.432000e+02 3.863900e+02 +0 678 -1.193020e+03 3.570500e+02 +4 678 -4.773999e+01 3.821300e+02 +5 678 -8.199100e+02 6.016300e+02 +7 678 -9.689100e+02 4.580200e+02 +14 678 -1.252500e+02 3.156900e+02 +15 678 6.955601e+02 2.524200e+02 +16 678 -5.063500e+02 4.036799e+02 +0 679 -1.231350e+03 3.593201e+02 +4 679 -6.593005e+01 3.822400e+02 +5 679 -8.456200e+02 5.983101e+02 +7 679 -9.953900e+02 4.593401e+02 +14 679 -1.408300e+02 3.170600e+02 +15 679 6.750400e+02 2.527900e+02 +16 679 -5.260400e+02 4.038300e+02 +0 680 -1.374440e+03 3.781500e+02 +4 680 -1.369301e+02 3.886000e+02 +5 680 -9.455100e+02 5.927900e+02 +7 680 -1.105900e+03 4.730801e+02 +19 680 2.251000e+02 4.013600e+02 +0 681 6.395801e+02 3.882300e+02 +4 681 9.399399e+02 4.436000e+02 +0 682 6.018501e+02 4.098201e+02 +5 682 4.626100e+02 8.746700e+02 +0 683 6.018501e+02 4.098201e+02 +4 683 9.175400e+02 4.497000e+02 +0 684 4.938999e+02 4.165100e+02 +2 684 -3.382600e+02 3.676500e+02 +4 684 8.534500e+02 4.476200e+02 +5 684 3.775900e+02 8.623101e+02 +7 684 2.056000e+02 5.011799e+02 +8 684 -8.182700e+02 6.216600e+02 +10 684 -2.745699e+02 -2.413101e+02 +11 684 2.874399e+02 3.473400e+02 +0 685 6.108999e+02 4.203800e+02 +4 685 9.234700e+02 4.574299e+02 +0 686 5.512100e+02 4.483201e+02 +4 686 8.873799e+02 4.692100e+02 +0 687 -9.341700e+02 4.591000e+02 +4 687 7.137000e+01 4.459099e+02 +15 687 8.285699e+02 3.251200e+02 +0 688 -1.075200e+03 4.788900e+02 +4 688 5.609985e+00 4.501200e+02 +10 688 -1.288780e+03 -1.640800e+02 +15 688 7.552700e+02 3.299900e+02 +16 688 -4.527100e+02 4.778800e+02 +0 689 -1.647610e+03 4.795500e+02 +4 689 -2.797100e+02 4.390601e+02 +5 689 -1.153640e+03 6.321100e+02 +15 689 4.266500e+02 3.150000e+02 +16 689 -7.754600e+02 4.663900e+02 +19 689 -4.306006e+01 4.841500e+02 +0 690 -1.136080e+03 4.849700e+02 +4 690 -2.371997e+01 4.511400e+02 +10 690 -1.326570e+03 -1.589600e+02 +16 690 -4.841000e+02 4.797200e+02 +19 690 4.393400e+02 5.193201e+02 +0 691 -1.290810e+03 4.864700e+02 +4 691 -9.693005e+01 4.462700e+02 +5 691 -9.051000e+02 6.810000e+02 +7 691 -1.042630e+03 5.588300e+02 +10 691 -1.427390e+03 -1.573101e+02 +14 691 -1.657900e+02 3.760600e+02 +15 691 6.403400e+02 3.249399e+02 +16 691 -5.620900e+02 4.747700e+02 +20 691 -1.295610e+03 -2.409003e+01 +0 692 -1.298720e+03 4.973800e+02 +4 692 -1.024900e+02 4.526599e+02 +5 692 -9.138200e+02 6.882700e+02 +14 692 -1.710400e+02 3.821000e+02 +15 692 6.333600e+02 3.326100e+02 +16 692 -5.694500e+02 4.814299e+02 +0 693 -1.197910e+03 5.315701e+02 +4 693 -5.275000e+01 4.737100e+02 +5 693 -8.487900e+02 7.265400e+02 +14 693 -1.268600e+02 3.969600e+02 +19 693 3.841100e+02 5.619500e+02 +0 694 -1.211930e+03 5.326500e+02 +4 694 -5.983997e+01 4.736599e+02 +5 694 -8.585600e+02 7.252500e+02 +7 694 -9.876500e+02 5.975200e+02 +10 694 -1.371730e+03 -1.225000e+02 +14 694 -1.329600e+02 3.974700e+02 +15 694 6.828300e+02 3.559700e+02 +16 694 -5.219700e+02 5.037100e+02 +19 694 3.715900e+02 5.617100e+02 +0 695 -7.778700e+02 5.927900e+02 +4 695 1.378101e+02 5.307200e+02 +0 696 -2.335699e+02 6.218401e+02 +7 696 6.202500e+02 2.990701e+02 +9 696 5.207800e+02 6.176001e+01 +13 696 1.024910e+03 4.389700e+02 +20 696 3.084998e+01 -2.725699e+02 +0 697 -1.219190e+03 6.494200e+02 +4 697 -6.682996e+01 5.343800e+02 +0 698 -9.237400e+02 7.167800e+02 +4 698 7.087000e+01 5.869800e+02 +7 698 -8.154500e+02 7.541000e+02 +14 698 -2.723001e+01 4.814299e+02 +15 698 8.274301e+02 4.848900e+02 +16 698 -3.913100e+02 6.238201e+02 +19 698 6.116700e+02 7.647800e+02 +0 699 -1.061720e+03 7.467700e+02 +4 699 5.810059e+00 5.949700e+02 +7 699 -8.989000e+02 7.735200e+02 +14 699 -7.628000e+01 4.965500e+02 +15 699 7.559700e+02 4.936500e+02 +16 699 -4.574700e+02 6.342500e+02 +0 700 -1.114840e+03 7.654600e+02 +4 700 -2.075000e+01 6.020800e+02 +19 700 4.440900e+02 7.991300e+02 +0 701 -1.274220e+03 7.844000e+02 +4 701 -9.941003e+01 6.061500e+02 +5 701 -9.438600e+02 9.021400e+02 +19 701 2.966899e+02 8.065500e+02 +0 702 -1.349510e+03 8.234399e+02 +4 702 -1.369100e+02 6.243800e+02 +5 702 -1.002870e+03 9.208900e+02 +0 703 1.344530e+03 -9.766003e+01 +8 703 -2.929300e+02 -1.641500e+02 +0 704 7.566399e+02 -7.189001e+01 +4 704 1.008150e+03 1.799099e+02 +0 705 7.625500e+02 -6.043994e+01 +4 705 1.011940e+03 1.863201e+02 +0 706 8.270100e+02 -5.785999e+01 +5 706 6.963000e+02 5.545601e+02 +0 707 1.273400e+03 1.109998e+01 +8 707 -4.612100e+02 9.765997e+01 +0 708 -1.438640e+03 1.721997e+01 +4 708 -1.616700e+02 2.045400e+02 +19 708 1.761300e+02 5.002002e+01 +0 709 8.227400e+02 3.295996e+01 +4 709 1.053380e+03 2.432000e+02 +5 709 6.828300e+02 6.228000e+02 +0 710 8.018799e+02 3.346997e+01 +4 710 1.039650e+03 2.427700e+02 +5 710 6.651801e+02 6.195200e+02 +0 711 -1.391520e+03 3.820996e+01 +7 711 -1.100390e+03 2.048101e+02 +15 711 5.910500e+02 6.240002e+01 +16 711 -5.970500e+02 2.193700e+02 +19 711 2.249700e+02 7.051001e+01 +0 712 -9.830800e+02 4.983997e+01 +4 712 5.581995e+01 2.282400e+02 +7 712 -8.240800e+02 2.232000e+02 +15 712 8.103199e+02 7.539001e+01 +16 712 -3.926800e+02 2.378600e+02 +0 713 -1.136040e+03 5.496997e+01 +4 713 -1.491003e+01 2.272900e+02 +7 713 -9.179800e+02 2.227800e+02 +14 713 -1.015000e+02 1.769200e+02 +15 713 7.312800e+02 7.510999e+01 +16 713 -4.652300e+02 2.355700e+02 +18 713 -1.413170e+03 -8.107996e+01 +20 713 -1.219760e+03 -2.724200e+02 +0 714 6.806799e+02 5.956995e+01 +4 714 9.621699e+02 2.531000e+02 +0 715 -1.304610e+03 6.000000e+01 +4 715 -9.510999e+01 2.271200e+02 +14 715 -1.703100e+02 1.798200e+02 +15 715 6.393700e+02 7.577002e+01 +16 715 -5.521800e+02 2.332500e+02 +0 716 -1.425540e+03 6.196997e+01 +4 716 -1.548800e+02 2.266000e+02 +15 716 5.698101e+02 7.603998e+01 +16 716 -6.194500e+02 2.312300e+02 +19 716 1.898400e+02 9.263000e+01 +0 717 -1.135550e+03 6.369995e+01 +4 717 -1.447998e+01 2.316799e+02 +7 717 -9.170400e+02 2.291200e+02 +14 717 -1.005200e+02 1.803700e+02 +15 717 7.322000e+02 7.996997e+01 +18 717 -1.411780e+03 -7.566003e+01 +20 717 -1.218230e+03 -2.674301e+02 +0 718 6.573501e+02 7.012000e+01 +4 718 9.477300e+02 2.580901e+02 +0 719 -1.489540e+03 7.058997e+01 +4 719 -1.857100e+02 2.305000e+02 +5 719 -9.757400e+02 3.634500e+02 +14 719 -2.524500e+02 1.860500e+02 +15 719 5.346700e+02 8.083002e+01 +16 719 -6.541400e+02 2.350800e+02 +19 719 1.315500e+02 1.002200e+02 +0 720 8.324299e+02 7.445996e+01 +6 720 -1.456000e+02 -8.796997e+01 +0 721 8.745400e+02 7.723999e+01 +4 721 1.091110e+03 2.731100e+02 +5 721 7.275800e+02 6.660800e+02 +8 721 -1.574100e+02 5.445001e+01 +0 722 8.745400e+02 7.723999e+01 +5 722 7.267600e+02 6.675000e+02 +8 722 -1.574100e+02 5.445001e+01 +0 723 -1.194600e+03 8.448999e+01 +4 723 -4.291003e+01 2.415701e+02 +7 723 -9.585500e+02 2.447800e+02 +14 723 -1.250100e+02 1.906500e+02 +15 723 6.989500e+02 9.178998e+01 +0 724 -1.041470e+03 8.671997e+01 +4 724 2.806006e+01 2.455000e+02 +14 724 -6.731000e+01 1.904100e+02 +15 724 7.802300e+02 9.515997e+01 +0 725 -1.318760e+03 8.846997e+01 +4 725 -1.024800e+02 2.415901e+02 +7 725 -1.047380e+03 2.454000e+02 +14 725 -1.764000e+02 1.929600e+02 +15 725 6.313400e+02 9.242999e+01 +16 725 -5.609300e+02 2.492000e+02 +0 726 -1.318760e+03 8.846997e+01 +4 726 -1.024800e+02 2.415901e+02 +7 726 -1.047380e+03 2.454000e+02 +14 726 -1.764000e+02 1.929600e+02 +15 726 6.313400e+02 9.242999e+01 +0 727 -1.363840e+03 8.958997e+01 +4 727 -1.247400e+02 2.417000e+02 +7 727 -1.082180e+03 2.460200e+02 +14 727 -1.965600e+02 1.940900e+02 +15 727 6.058800e+02 9.272998e+01 +16 727 -5.851400e+02 2.487800e+02 +19 727 2.477000e+02 1.215601e+02 +0 728 -1.416160e+03 9.044995e+01 +4 728 -1.498600e+02 2.416200e+02 +5 728 -9.285800e+02 3.863101e+02 +10 728 -1.536960e+03 -4.609399e+02 +15 728 5.758199e+02 9.278998e+01 +16 728 -6.135000e+02 2.481500e+02 +19 728 1.988000e+02 1.207800e+02 +0 729 -1.453720e+03 9.154004e+01 +4 729 -1.695100e+02 2.415601e+02 +14 729 -2.375400e+02 1.952000e+02 +15 729 5.530900e+02 9.297998e+01 +16 729 -6.357200e+02 2.474800e+02 +19 729 1.628800e+02 1.207800e+02 +0 730 -1.199230e+03 9.306995e+01 +4 730 -4.623999e+01 2.457100e+02 +7 730 -9.640800e+02 2.512000e+02 +14 730 -1.278000e+02 1.941600e+02 +15 730 6.959800e+02 9.644000e+01 +0 731 1.281250e+03 9.510999e+01 +8 731 -4.305600e+02 2.957600e+02 +0 732 -1.056600e+03 9.471997e+01 +4 732 2.176001e+01 2.497100e+02 +7 732 -8.690300e+02 2.556799e+02 +14 732 -7.110999e+01 1.947200e+02 +15 732 7.733101e+02 1.002900e+02 +0 733 -1.369200e+03 9.812000e+01 +4 733 -1.275601e+02 2.455601e+02 +5 733 -8.986700e+02 3.976400e+02 +15 733 6.021500e+02 9.687000e+01 +0 734 1.091030e+03 1.048600e+02 +8 734 2.116000e+02 8.482001e+01 +16 734 6.818900e+02 3.322000e+02 +0 735 -1.534800e+03 1.067400e+02 +4 735 -2.095200e+02 2.482500e+02 +15 735 5.068400e+02 1.014800e+02 +0 736 7.226499e+02 1.121500e+02 +5 736 5.906000e+02 6.680000e+02 +0 737 1.273690e+03 1.175200e+02 +8 737 -4.361100e+02 3.436600e+02 +0 738 6.863701e+02 1.171600e+02 +4 738 9.665601e+02 2.863301e+02 +5 738 5.599399e+02 6.662700e+02 +0 739 1.098350e+03 1.200200e+02 +8 739 2.237800e+02 1.087900e+02 +0 740 7.685200e+02 1.199700e+02 +4 740 1.018390e+03 2.919500e+02 +5 740 6.269200e+02 6.810800e+02 +0 741 6.575000e+02 1.193600e+02 +4 741 9.480801e+02 2.867300e+02 +5 741 5.350300e+02 6.642000e+02 +0 742 1.665650e+03 1.211000e+02 +6 742 9.738900e+02 -4.240002e+01 +8 742 9.565200e+02 1.243500e+02 +9 742 5.622300e+02 1.518301e+02 +18 742 7.447998e+01 -3.355005e+01 +0 743 1.706650e+03 1.223600e+02 +7 743 9.872700e+02 2.851599e+02 +9 743 5.917100e+02 1.528700e+02 +17 743 -7.561200e+02 3.308401e+02 +18 743 9.190002e+01 -3.295996e+01 +0 744 8.611899e+02 1.255300e+02 +8 744 -1.815700e+02 1.311000e+02 +0 745 9.050100e+02 1.344500e+02 +4 745 1.112230e+03 3.091899e+02 +5 745 7.475601e+02 7.164399e+02 +8 745 -1.079200e+02 1.414300e+02 +0 746 9.720200e+02 1.445100e+02 +4 746 1.162440e+03 3.221200e+02 +5 746 8.099199e+02 7.381100e+02 +8 746 7.420044e+00 1.533800e+02 +0 747 8.622700e+02 1.440000e+02 +4 747 1.083080e+03 3.129500e+02 +0 748 9.372600e+02 1.543301e+02 +8 748 -5.015002e+01 1.727300e+02 +16 748 6.092700e+02 3.476600e+02 +0 749 8.377600e+02 1.542800e+02 +4 749 1.066160e+03 3.169600e+02 +5 749 6.859100e+02 7.198400e+02 +0 750 8.727500e+02 1.607000e+02 +4 750 1.089860e+03 3.232900e+02 +5 750 7.153900e+02 7.311000e+02 +8 750 -1.626000e+02 1.847100e+02 +0 751 9.647600e+02 1.627300e+02 +4 751 1.157680e+03 3.326000e+02 +5 751 8.022300e+02 7.510200e+02 +8 751 -3.559998e+00 1.821900e+02 +9 751 -1.471801e+02 2.478600e+02 +10 751 -1.032000e+02 -3.811500e+02 +11 751 4.816200e+02 1.840300e+02 +12 751 -6.914800e+02 -4.761899e+02 +13 751 -1.151130e+03 5.074199e+02 +16 751 6.214500e+02 3.556500e+02 +18 751 -3.587600e+02 3.504004e+01 +20 751 -3.033400e+02 -1.672700e+02 +0 752 -1.438630e+03 1.670701e+02 +4 752 -1.642400e+02 2.804900e+02 +5 752 -9.571400e+02 4.370400e+02 +14 752 -2.322000e+02 2.301300e+02 +0 753 -1.451130e+03 1.667100e+02 +4 753 -1.703000e+02 2.793700e+02 +0 754 5.001799e+02 1.680901e+02 +2 754 -3.303900e+02 7.223999e+01 +3 754 -1.018400e+03 2.937300e+02 +4 754 8.553501e+02 3.076899e+02 +5 754 4.081300e+02 6.769200e+02 +9 754 -3.575000e+02 1.929700e+02 +10 754 -2.699900e+02 -4.019100e+02 +11 754 2.946000e+02 1.301300e+02 +12 754 -9.001600e+02 -5.171600e+02 +18 754 -4.973900e+02 3.510010e+00 +20 754 -4.220400e+02 -1.950601e+02 +0 755 9.045801e+02 1.737200e+02 +8 755 -1.087300e+02 2.024000e+02 +0 756 5.469700e+02 1.750500e+02 +2 756 -2.931600e+02 8.088000e+01 +4 756 8.822500e+02 3.130601e+02 +5 756 4.425900e+02 6.886899e+02 +9 756 -3.272700e+02 1.999399e+02 +10 756 -2.472900e+02 -3.961899e+02 +11 756 3.227900e+02 1.382900e+02 +12 756 -8.730500e+02 -5.100800e+02 +18 756 -4.781500e+02 8.479980e+00 +20 756 -4.053101e+02 -1.902500e+02 +0 757 -9.120900e+02 1.812800e+02 +4 757 8.673999e+01 2.985500e+02 +7 757 -7.873300e+02 3.276100e+02 +15 757 8.456000e+02 1.562100e+02 +19 757 6.454600e+02 2.247000e+02 +0 758 9.535601e+02 1.883700e+02 +4 758 1.149890e+03 3.475300e+02 +0 759 5.882300e+02 1.976400e+02 +5 759 4.723101e+02 7.116100e+02 +0 760 8.550300e+02 1.987700e+02 +4 760 1.079040e+03 3.439800e+02 +5 760 6.973800e+02 7.573101e+02 +0 761 6.715400e+02 1.985801e+02 +5 761 5.401000e+02 7.263900e+02 +0 762 -8.582500e+02 2.017400e+02 +4 762 1.096700e+02 3.118900e+02 +0 763 -8.183000e+02 2.059800e+02 +4 763 1.274000e+02 3.160100e+02 +7 763 -7.449400e+02 3.516799e+02 +10 763 -1.166840e+03 -3.640800e+02 +14 763 5.679993e+00 2.439600e+02 +15 763 8.877800e+02 1.759500e+02 +16 763 -3.272500e+02 3.332900e+02 +19 763 7.170200e+02 2.523301e+02 +0 764 9.265500e+02 2.148700e+02 +4 764 1.129320e+03 3.601100e+02 +0 765 7.673301e+02 2.253500e+02 +4 765 1.019380e+03 3.534800e+02 +5 765 6.164000e+02 7.618201e+02 +7 765 3.515300e+02 3.777600e+02 +0 766 -9.044500e+02 2.251100e+02 +7 766 -7.875300e+02 3.607800e+02 +19 766 6.481399e+02 2.683000e+02 +0 767 -1.298550e+03 2.257000e+02 +4 767 -9.581995e+01 3.118301e+02 +5 767 -8.705500e+02 4.950100e+02 +7 767 -1.039430e+03 3.530701e+02 +14 767 -1.689400e+02 2.557200e+02 +15 767 6.394399e+02 1.725900e+02 +16 767 -5.570300e+02 3.262700e+02 +19 767 3.030601e+02 2.561500e+02 +0 768 -1.083470e+03 2.337700e+02 +4 768 6.390015e+00 3.211899e+02 +7 768 -8.915000e+02 3.633800e+02 +14 768 -8.197000e+01 2.580800e+02 +15 768 7.563600e+02 1.826700e+02 +16 768 -4.472400e+02 3.380601e+02 +0 769 -1.298990e+03 2.352300e+02 +5 769 -8.718200e+02 5.019700e+02 +0 770 -1.422980e+03 2.371200e+02 +4 770 -1.569500e+02 3.159399e+02 +5 770 -9.567500e+02 4.877200e+02 +15 770 5.689200e+02 1.771400e+02 +19 770 1.870900e+02 2.623500e+02 +0 771 -1.184500e+03 2.398800e+02 +4 771 -4.146997e+01 3.217700e+02 +5 771 -7.953500e+02 5.197200e+02 +7 771 -9.586200e+02 3.661599e+02 +14 771 -1.214700e+02 2.615800e+02 +15 771 7.021500e+02 1.836700e+02 +16 771 -4.969100e+02 3.383500e+02 +0 772 -1.245350e+03 2.431300e+02 +4 772 -7.006995e+01 3.221200e+02 +7 772 -1.000910e+03 3.677700e+02 +15 772 6.690400e+02 1.841200e+02 +16 772 -5.291600e+02 3.379399e+02 +19 772 3.513900e+02 2.753301e+02 +0 773 7.913401e+02 2.442900e+02 +4 773 1.035450e+03 3.672300e+02 +6 773 -1.869700e+02 1.456900e+02 +0 774 -1.264670e+03 2.436200e+02 +7 774 -1.016440e+03 3.681200e+02 +15 774 6.575500e+02 1.841100e+02 +16 774 -5.393900e+02 3.380601e+02 +19 774 3.331000e+02 2.751500e+02 +0 775 -1.285410e+03 2.448401e+02 +4 775 -9.006006e+01 3.223401e+02 +14 775 -1.633900e+02 2.645600e+02 +19 775 3.140800e+02 2.754299e+02 +0 776 -1.713620e+03 2.454299e+02 +4 776 -3.080500e+02 3.182900e+02 +5 776 -1.161550e+03 4.579700e+02 +0 777 -1.582850e+03 2.471200e+02 +4 777 -2.403900e+02 3.202400e+02 +14 777 -3.030400e+02 2.680800e+02 +19 777 2.962000e+01 2.661799e+02 +0 778 -1.582850e+03 2.471200e+02 +4 778 -2.403900e+02 3.202400e+02 +5 778 -1.070480e+03 4.751100e+02 +14 778 -3.030400e+02 2.680800e+02 +15 778 4.701200e+02 1.822300e+02 +19 778 2.962000e+01 2.661799e+02 +0 779 5.815000e+02 2.475601e+02 +2 779 -2.701000e+02 1.689900e+02 +4 779 9.033701e+02 3.560300e+02 +5 779 4.626100e+02 7.479700e+02 +7 779 2.561300e+02 3.834399e+02 +9 779 -3.090800e+02 2.695000e+02 +10 779 -2.328700e+02 -3.480300e+02 +11 779 3.394600e+02 2.055400e+02 +12 779 -8.548100e+02 -4.557200e+02 +0 780 8.011899e+02 2.490701e+02 +4 780 1.042240e+03 3.703800e+02 +5 780 6.435300e+02 7.864700e+02 +0 781 -1.449200e+03 2.495601e+02 +4 781 -1.702500e+02 3.221500e+02 +5 781 -9.765000e+02 4.935500e+02 +15 781 5.533500e+02 1.844100e+02 +16 781 -6.404900e+02 3.370000e+02 +0 782 -1.616210e+03 2.540300e+02 +4 782 -2.591000e+02 3.236599e+02 +14 782 -3.214800e+02 2.716300e+02 +15 782 4.484000e+02 1.864300e+02 +19 782 -4.420044e+00 2.712400e+02 +0 783 6.375801e+02 2.550400e+02 +7 783 2.845500e+02 3.909500e+02 +0 784 -1.484460e+03 2.583101e+02 +4 784 -1.868500e+02 3.254199e+02 +5 784 -1.000750e+03 4.946899e+02 +14 784 -2.513300e+02 2.722000e+02 +15 784 5.346000e+02 1.885900e+02 +16 784 -6.598500e+02 3.399900e+02 +0 785 -1.537680e+03 2.582900e+02 +4 785 -2.147300e+02 3.251200e+02 +14 785 -2.769400e+02 2.732600e+02 +19 785 7.871997e+01 2.792000e+02 +0 786 8.564099e+02 2.654700e+02 +4 786 1.080650e+03 3.860500e+02 +5 786 6.919000e+02 8.105200e+02 +0 787 1.465190e+03 2.699900e+02 +8 787 6.898800e+02 3.492500e+02 +16 787 9.123199e+02 4.040500e+02 +0 788 1.480870e+03 2.709800e+02 +8 788 7.124600e+02 3.490000e+02 +16 788 9.204500e+02 4.036500e+02 +0 789 -8.354200e+02 2.813700e+02 +4 789 1.182900e+02 3.561000e+02 +7 789 -7.580500e+02 4.106400e+02 +10 789 -1.175380e+03 -3.072800e+02 +15 789 8.772500e+02 2.217900e+02 +16 789 -3.392600e+02 3.755100e+02 +18 789 -1.295750e+03 8.354004e+01 +19 789 6.994700e+02 3.283000e+02 +20 789 -1.114770e+03 -1.289399e+02 +0 790 8.394600e+02 2.858401e+02 +6 790 -1.220000e+02 1.856600e+02 +8 790 -2.167200e+02 3.826500e+02 +0 791 6.006299e+02 3.104199e+02 +4 791 9.155801e+02 3.915400e+02 +5 791 4.729600e+02 7.970200e+02 +7 791 2.638800e+02 4.271799e+02 +8 791 -6.360900e+02 4.419100e+02 +12 791 -8.455400e+02 -4.127000e+02 +0 792 6.006299e+02 3.104199e+02 +7 792 2.638800e+02 4.271799e+02 +10 792 -2.275900e+02 -3.074100e+02 +12 792 -8.455400e+02 -4.127000e+02 +13 792 -1.704270e+03 8.817000e+02 +18 792 -4.610800e+02 8.696997e+01 +20 792 -3.905699e+02 -1.233101e+02 +0 793 6.342800e+02 3.122100e+02 +4 793 9.363601e+02 3.962000e+02 +5 793 4.981300e+02 8.063500e+02 +0 794 -1.664550e+03 3.220601e+02 +4 794 -2.852400e+02 3.579399e+02 +0 795 5.712600e+02 3.372500e+02 +4 795 8.988000e+02 4.060701e+02 +5 795 4.451600e+02 8.130701e+02 +8 795 -6.877300e+02 4.867000e+02 +0 796 7.461799e+02 3.443101e+02 +5 796 5.986500e+02 8.590699e+02 +0 797 -1.304570e+03 3.615300e+02 +4 797 -1.016200e+02 3.814299e+02 +5 797 -8.954400e+02 5.902000e+02 +7 797 -1.049390e+03 4.601300e+02 +14 797 -1.718900e+02 3.181900e+02 +15 797 6.340100e+02 2.516300e+02 +16 797 -5.647300e+02 4.025900e+02 +19 797 2.925200e+02 3.880000e+02 +0 798 -1.349410e+03 3.833500e+02 +4 798 -1.240900e+02 3.920500e+02 +5 798 -9.299300e+02 5.993900e+02 +14 798 -1.920800e+02 3.287000e+02 +15 798 6.081000e+02 2.634000e+02 +16 798 -5.906700e+02 4.148800e+02 +19 798 2.500400e+02 4.073301e+02 +0 799 6.742700e+02 3.873900e+02 +4 799 9.651399e+02 4.514900e+02 +5 799 5.317100e+02 8.790400e+02 +0 800 -1.390520e+03 3.883401e+02 +5 800 -9.584400e+02 5.983700e+02 +7 800 -1.116900e+03 4.821699e+02 +14 800 -2.100600e+02 3.319300e+02 +15 800 5.848300e+02 2.658101e+02 +16 800 -6.133900e+02 4.165200e+02 +19 800 2.114900e+02 4.108800e+02 +0 801 5.805701e+02 4.035000e+02 +4 801 9.044199e+02 4.445000e+02 +5 801 4.455699e+02 8.662600e+02 +8 801 -6.687600e+02 5.939100e+02 +0 802 -1.600760e+03 4.120901e+02 +4 802 -2.541500e+02 4.045601e+02 +5 802 -1.109660e+03 5.894500e+02 +15 802 4.559200e+02 2.770100e+02 +16 802 -7.432100e+02 4.275500e+02 +19 802 6.300049e+00 4.230500e+02 +0 803 -1.380420e+03 4.163700e+02 +4 803 -1.398199e+02 4.086200e+02 +5 803 -9.561500e+02 6.193000e+02 +7 803 -1.108770e+03 5.043000e+02 +14 803 -2.051300e+02 3.448300e+02 +15 803 5.908000e+02 2.822300e+02 +19 803 2.210100e+02 4.388101e+02 +0 804 -1.380420e+03 4.163700e+02 +4 804 -1.398199e+02 4.086200e+02 +5 804 -9.561500e+02 6.193000e+02 +7 804 -1.108770e+03 5.043000e+02 +14 804 -2.051300e+02 3.448300e+02 +15 804 5.908000e+02 2.822300e+02 +19 804 2.210100e+02 4.388101e+02 +0 805 -1.588690e+03 4.260400e+02 +4 805 -2.478300e+02 4.118500e+02 +5 805 -1.103550e+03 6.007200e+02 +15 805 4.638101e+02 2.852200e+02 +16 805 -7.358000e+02 4.357400e+02 +19 805 1.729004e+01 4.371100e+02 +0 806 -1.599900e+03 4.257200e+02 +4 806 -2.541300e+02 4.115300e+02 +5 806 -1.111740e+03 5.990400e+02 +15 806 4.566300e+02 2.848300e+02 +19 806 6.920044e+00 4.362400e+02 +0 807 5.631599e+02 4.430100e+02 +4 807 8.948501e+02 4.662500e+02 +5 807 4.281100e+02 8.932300e+02 +0 808 -9.754500e+02 4.449500e+02 +7 808 -8.336300e+02 5.322000e+02 +10 808 -1.232960e+03 -1.891600e+02 +14 808 -4.344000e+01 3.544900e+02 +15 808 8.080699e+02 3.140701e+02 +0 809 -1.380040e+03 4.446000e+02 +4 809 -1.396300e+02 4.234000e+02 +5 809 -9.601100e+02 6.397800e+02 +7 809 -1.109540e+03 5.271100e+02 +14 809 -2.046300e+02 3.579000e+02 +15 809 5.912800e+02 2.988500e+02 +19 809 2.203800e+02 4.663401e+02 +0 810 -9.868100e+02 4.512700e+02 +4 810 4.730005e+01 4.389700e+02 +10 810 -1.238360e+03 -1.851700e+02 +14 810 -4.694000e+01 3.570700e+02 +15 810 8.020601e+02 3.173000e+02 +16 810 -4.085800e+02 4.646799e+02 +19 810 5.727300e+02 4.918700e+02 +20 810 -1.157510e+03 -3.937000e+01 +0 811 -1.290080e+03 4.762500e+02 +4 811 -9.678003e+01 4.414299e+02 +5 811 -9.035100e+02 6.739100e+02 +7 811 -1.044020e+03 5.520400e+02 +14 811 -1.665100e+02 3.717800e+02 +15 811 6.398600e+02 3.197000e+02 +0 812 4.971899e+02 4.842200e+02 +4 812 8.563501e+02 4.869399e+02 +5 812 3.731000e+02 9.148199e+02 +8 812 -8.090700e+02 7.312900e+02 +0 813 4.417400e+02 4.870400e+02 +2 813 -3.886500e+02 4.532100e+02 +4 813 8.238799e+02 4.858800e+02 +5 813 3.313800e+02 9.091000e+02 +7 813 1.729301e+02 5.526599e+02 +8 813 -9.047900e+02 7.402700e+02 +10 813 -3.021899e+02 -1.962000e+02 +11 813 2.502200e+02 4.082700e+02 +18 813 -5.233900e+02 1.840500e+02 +0 814 4.417400e+02 4.870400e+02 +5 814 3.313800e+02 9.091000e+02 +8 814 -9.047900e+02 7.402700e+02 +0 815 -7.824500e+02 4.948301e+02 +4 815 1.382700e+02 4.755701e+02 +14 815 1.526001e+01 3.761300e+02 +15 815 8.985500e+02 3.585200e+02 +16 815 -3.236600e+02 5.020500e+02 +19 815 7.318999e+02 5.477300e+02 +0 816 -1.401780e+03 4.964199e+02 +4 816 -1.528199e+02 4.503800e+02 +5 816 -9.830500e+02 6.743101e+02 +15 816 5.759301e+02 3.289700e+02 +19 816 1.959399e+02 5.157100e+02 +0 817 -1.609180e+03 4.968600e+02 +4 817 -2.610500e+02 4.484600e+02 +15 817 4.485000e+02 3.256799e+02 +16 817 -7.514600e+02 4.771100e+02 +0 818 -1.343170e+03 5.008301e+02 +4 818 -1.241600e+02 4.532300e+02 +0 819 -1.504480e+03 5.008401e+02 +4 819 -2.072300e+02 4.512800e+02 +0 820 -9.174000e+02 5.025601e+02 +4 820 7.879004e+01 4.702700e+02 +7 820 -8.018400e+02 5.805900e+02 +14 820 -2.301999e+01 3.804200e+02 +15 820 8.368300e+02 3.525900e+02 +16 820 -3.789200e+02 4.979000e+02 +19 820 6.283799e+02 5.480601e+02 +0 821 -9.872400e+02 5.136300e+02 +7 821 -8.444400e+02 5.869900e+02 +14 821 -4.838000e+01 3.861899e+02 +19 821 5.670000e+02 5.555000e+02 +0 822 -1.057830e+03 5.251300e+02 +4 822 1.318994e+01 4.749399e+02 +7 822 -8.849900e+02 5.936200e+02 +14 822 -7.235999e+01 3.922000e+02 +15 822 7.649200e+02 3.584700e+02 +16 822 -4.451800e+02 5.043201e+02 +19 822 5.082000e+02 5.630500e+02 +0 823 -1.191840e+03 5.400400e+02 +4 823 -5.123999e+01 4.781699e+02 +5 823 -8.469100e+02 7.333900e+02 +7 823 -9.753600e+02 6.037000e+02 +10 823 -1.359470e+03 -1.171500e+02 +15 823 6.924200e+02 3.613600e+02 +19 823 3.878800e+02 5.706300e+02 +0 824 -1.218220e+03 5.422000e+02 +4 824 -6.308997e+01 4.783600e+02 +5 824 -8.648100e+02 7.314600e+02 +7 824 -9.935600e+02 6.049100e+02 +10 824 -1.377110e+03 -1.155900e+02 +14 824 -1.358200e+02 4.017800e+02 +15 824 6.785699e+02 3.615500e+02 +16 824 -5.266100e+02 5.087200e+02 +18 824 -1.466160e+03 2.439500e+02 +19 824 3.644000e+02 5.705701e+02 +20 824 -1.258630e+03 9.239990e+00 +0 825 -1.285180e+03 5.771500e+02 +4 825 -9.806995e+01 4.949800e+02 +15 825 6.390300e+02 3.800701e+02 +0 826 -1.118720e+03 6.378900e+02 +4 826 -1.803003e+01 5.324500e+02 +19 826 4.492600e+02 6.718201e+02 +0 827 -1.283820e+03 6.531000e+02 +4 827 -9.783997e+01 5.345500e+02 +5 827 -9.273800e+02 8.032200e+02 +10 827 -1.419970e+03 -2.970996e+01 +14 827 -1.644900e+02 4.540900e+02 +15 827 6.395000e+02 4.244600e+02 +16 827 -5.668100e+02 5.702800e+02 +20 827 -1.292570e+03 7.502002e+01 +0 828 -8.841500e+02 6.606100e+02 +4 828 9.094995e+01 5.581200e+02 +7 828 -7.895100e+02 7.088201e+02 +10 828 -1.182080e+03 -2.706006e+01 +14 828 -1.270001e+01 4.540200e+02 +15 828 8.491600e+02 4.522500e+02 +16 828 -3.702300e+02 5.919399e+02 +19 828 6.486699e+02 7.102100e+02 +0 829 -8.662500e+02 6.637400e+02 +4 829 9.920996e+01 5.607200e+02 +0 830 -9.192100e+02 6.695100e+02 +4 830 7.452002e+01 5.606799e+02 +7 830 -8.089000e+02 7.141100e+02 +10 830 -1.199030e+03 -2.106995e+01 +14 830 -2.401999e+01 4.580701e+02 +15 830 8.317800e+02 4.549900e+02 +16 830 -3.855800e+02 5.947400e+02 +19 830 6.191500e+02 7.167900e+02 +0 831 -9.484900e+02 6.757800e+02 +4 831 6.089001e+01 5.618000e+02 +7 831 -8.252400e+02 7.176300e+02 +14 831 -3.391000e+01 4.610200e+02 +15 831 8.174700e+02 4.564700e+02 +19 831 5.946899e+02 7.211600e+02 +0 832 -9.304500e+02 6.806000e+02 +4 832 6.977002e+01 5.653000e+02 +10 832 -1.203430e+03 -1.273999e+01 +15 832 8.266300e+02 4.607600e+02 +19 832 6.097700e+02 7.279800e+02 +0 833 -9.304500e+02 6.806000e+02 +4 833 6.977002e+01 5.653000e+02 +7 833 -8.144500e+02 7.225601e+02 +15 833 8.266300e+02 4.607600e+02 +19 833 6.097700e+02 7.279800e+02 +0 834 -1.406580e+03 6.805500e+02 +4 834 -1.597500e+02 5.463600e+02 +16 834 -6.372800e+02 5.852300e+02 +19 834 1.823400e+02 6.939200e+02 +0 835 -9.425900e+02 6.834900e+02 +4 835 6.414001e+01 5.660000e+02 +7 835 -8.211800e+02 7.241500e+02 +10 835 -1.207540e+03 -1.148999e+01 +15 835 8.205800e+02 4.616799e+02 +19 835 5.999000e+02 7.297300e+02 +0 836 -9.425900e+02 6.834900e+02 +4 836 6.414001e+01 5.660000e+02 +7 836 -8.211800e+02 7.241500e+02 +10 836 -1.207540e+03 -1.148999e+01 +15 836 8.205800e+02 4.616799e+02 +19 836 5.999000e+02 7.297300e+02 +0 837 -9.556200e+02 6.862300e+02 +4 837 5.781006e+01 5.668900e+02 +10 837 -1.213520e+03 -9.819946e+00 +14 837 -3.541000e+01 4.663800e+02 +0 838 -9.556200e+02 6.862300e+02 +4 838 5.781006e+01 5.668900e+02 +7 838 -8.286800e+02 7.258000e+02 +15 838 8.138000e+02 4.621000e+02 +19 838 5.887300e+02 7.316000e+02 +0 839 -1.000870e+03 6.869000e+02 +4 839 3.633997e+01 5.650200e+02 +16 839 -4.244500e+02 6.007500e+02 +0 840 -1.015340e+03 6.899000e+02 +4 840 2.932996e+01 5.658101e+02 +7 840 -8.649300e+02 7.266899e+02 +10 840 -1.247910e+03 -6.949951e+00 +14 840 -5.753000e+01 4.685900e+02 +15 840 7.831801e+02 4.606500e+02 +16 840 -4.311800e+02 6.019600e+02 +19 840 5.373101e+02 7.307600e+02 +0 841 -9.835500e+02 6.926899e+02 +4 841 4.498999e+01 5.687000e+02 +0 842 -9.965400e+02 6.951600e+02 +4 842 3.933997e+01 5.689900e+02 +10 842 -1.234850e+03 -3.680054e+00 +14 842 -4.951999e+01 4.709100e+02 +15 842 7.935500e+02 4.648101e+02 +19 842 5.538000e+02 7.378600e+02 +0 843 -9.965400e+02 6.951600e+02 +4 843 3.933997e+01 5.689900e+02 +0 844 -1.060060e+03 6.979399e+02 +7 844 -8.935600e+02 7.322400e+02 +10 844 -1.273590e+03 -5.300293e-01 +14 844 -7.398001e+01 4.728101e+02 +15 844 7.599500e+02 4.627400e+02 +16 844 -4.524100e+02 6.045000e+02 +19 844 4.979900e+02 7.357100e+02 +0 845 -1.124130e+03 7.067200e+02 +4 845 -2.231995e+01 5.694500e+02 +7 845 -9.358700e+02 7.384900e+02 +10 845 -1.312020e+03 6.770020e+00 +19 845 4.410100e+02 7.400601e+02 +0 846 -1.139630e+03 7.090701e+02 +4 846 -2.960999e+01 5.699500e+02 +5 846 -8.379800e+02 8.649500e+02 +7 846 -9.461600e+02 7.400900e+02 +14 846 -1.052100e+02 4.789399e+02 +15 846 7.167600e+02 4.652100e+02 +19 846 4.272300e+02 7.412600e+02 +0 847 -1.154900e+03 7.107400e+02 +4 847 -3.713000e+01 5.702800e+02 +5 847 -8.488100e+02 8.639399e+02 +7 847 -9.568000e+02 7.413900e+02 +10 847 -1.331610e+03 1.051001e+01 +15 847 7.086100e+02 4.652800e+02 +16 847 -5.017400e+02 6.086899e+02 +19 847 4.134600e+02 7.420500e+02 +0 848 -1.103780e+03 7.130701e+02 +4 848 -1.221997e+01 5.731799e+02 +7 848 -9.219500e+02 7.433800e+02 +15 848 7.362700e+02 4.690701e+02 +19 848 4.588700e+02 7.482100e+02 +0 849 -1.699270e+03 7.175400e+02 +4 849 -3.129399e+02 5.623700e+02 +5 849 -1.230400e+03 7.973300e+02 +14 849 -3.655800e+02 4.901100e+02 +15 849 3.899700e+02 4.510800e+02 +16 849 -8.222900e+02 6.065400e+02 +19 849 -9.878003e+01 7.075100e+02 +0 850 -1.240810e+03 7.200400e+02 +4 850 -7.846997e+01 5.718300e+02 +5 850 -9.086400e+02 8.584700e+02 +7 850 -1.018140e+03 7.488000e+02 +10 850 -1.389170e+03 2.040002e+01 +14 850 -1.466400e+02 4.854299e+02 +15 850 6.616200e+02 4.663700e+02 +16 850 -5.472500e+02 6.114399e+02 +19 850 3.355601e+02 7.450300e+02 +0 851 -1.356660e+03 7.223600e+02 +4 851 -1.358400e+02 5.696700e+02 +15 851 5.964500e+02 4.629399e+02 +0 852 -1.437200e+03 7.492600e+02 +4 852 -1.761899e+02 5.820100e+02 +5 852 -1.048920e+03 8.532400e+02 +15 852 5.495900e+02 4.759000e+02 +16 852 -6.567400e+02 6.251600e+02 +19 852 1.545100e+02 7.589000e+02 +0 853 -1.192460e+03 7.766700e+02 +4 853 -5.625000e+01 6.037400e+02 +5 853 -8.864900e+02 9.068101e+02 +7 853 -9.835000e+02 7.946400e+02 +19 853 3.766400e+02 8.047200e+02 +0 854 -1.568340e+03 7.924900e+02 +4 854 -2.466899e+02 6.027900e+02 +5 854 -1.150210e+03 8.680200e+02 +10 854 -1.662750e+03 9.964001e+01 +14 854 -3.001800e+02 5.236899e+02 +15 854 4.671700e+02 4.972500e+02 +16 854 -7.424300e+02 6.502900e+02 +19 854 2.320996e+01 7.888800e+02 +0 855 -1.575890e+03 8.465200e+02 +4 855 -2.529399e+02 6.346300e+02 +14 855 -3.062500e+02 5.508300e+02 +15 855 4.598199e+02 5.322200e+02 +0 856 -1.464870e+03 8.484500e+02 +4 856 -1.958300e+02 6.354299e+02 +0 857 1.350920e+03 -1.498500e+02 +8 857 -2.811700e+02 -2.875800e+02 +0 858 7.699099e+02 -7.581006e+01 +4 858 1.016800e+03 1.777200e+02 +0 859 7.784800e+02 -7.446997e+01 +4 859 1.022220e+03 1.788401e+02 +0 860 7.418401e+02 -7.320996e+01 +4 860 9.988799e+02 1.787300e+02 +0 861 8.227900e+02 -6.934998e+01 +5 861 6.931000e+02 5.449700e+02 +0 862 8.315601e+02 7.390015e+00 +7 862 3.798300e+02 2.248301e+02 +0 863 -1.065510e+03 5.116003e+01 +4 863 1.796997e+01 2.265801e+02 +7 863 -8.716800e+02 2.217500e+02 +14 863 -7.426001e+01 1.746200e+02 +15 863 7.690601e+02 7.392999e+01 +16 863 -4.305300e+02 2.357100e+02 +20 863 -1.187700e+03 -2.723900e+02 +0 864 -1.230630e+03 5.655005e+01 +7 864 -9.806400e+02 2.221200e+02 +14 864 -1.389300e+02 1.780800e+02 +15 864 6.807600e+02 7.487000e+01 +16 864 -5.128200e+02 2.338900e+02 +20 864 -1.264360e+03 -2.736801e+02 +0 865 -9.818000e+02 5.831006e+01 +4 865 5.657996e+01 2.320500e+02 +7 865 -8.228600e+02 2.284299e+02 +10 865 -1.239940e+03 -4.815200e+02 +15 865 8.118400e+02 7.946002e+01 +16 865 -3.914000e+02 2.423500e+02 +0 866 -1.224340e+03 6.263000e+01 +4 866 -5.581995e+01 2.297200e+02 +16 866 -5.083200e+02 2.377400e+02 +0 867 9.347900e+02 6.625000e+01 +8 867 -5.613000e+01 3.415002e+01 +0 868 7.247600e+02 7.106995e+01 +4 868 9.900701e+02 2.616200e+02 +0 869 6.224500e+02 7.100000e+01 +4 869 9.262000e+02 2.571300e+02 +0 870 -9.969000e+02 7.563000e+01 +4 870 4.872998e+01 2.409199e+02 +7 870 -8.342500e+02 2.427000e+02 +10 870 -1.250880e+03 -4.683500e+02 +14 870 -5.053000e+01 1.853800e+02 +15 870 8.030000e+02 9.003003e+01 +0 871 8.540000e+02 7.700000e+01 +4 871 1.076470e+03 2.720100e+02 +5 871 7.082400e+02 6.634000e+02 +8 871 -1.944600e+02 5.609003e+01 +0 872 9.354299e+02 7.763000e+01 +8 872 -5.534998e+01 5.309003e+01 +0 873 -1.033170e+03 7.767004e+01 +4 873 3.229004e+01 2.413101e+02 +7 873 -8.548500e+02 2.432200e+02 +15 873 7.847700e+02 9.053998e+01 +0 874 -1.080830e+03 7.951001e+01 +4 874 1.001001e+01 2.410200e+02 +7 874 -8.847300e+02 2.431599e+02 +14 874 -8.104999e+01 1.874100e+02 +15 874 7.595699e+02 9.021002e+01 +16 874 -4.395400e+02 2.512100e+02 +0 875 -1.063710e+03 8.002002e+01 +4 875 1.884998e+01 2.416500e+02 +7 875 -8.724100e+02 2.443101e+02 +14 875 -7.376001e+01 1.878100e+02 +15 875 7.694700e+02 9.122998e+01 +16 875 -4.302100e+02 2.521500e+02 +18 875 -1.376340e+03 -6.185999e+01 +20 875 -1.187070e+03 -2.558000e+02 +0 876 -1.122710e+03 8.168005e+01 +4 876 -9.290039e+00 2.413900e+02 +0 877 -1.150530e+03 8.270996e+01 +4 877 -2.246997e+01 2.414600e+02 +7 877 -9.296700e+02 2.442300e+02 +14 877 -1.075200e+02 1.894400e+02 +15 877 7.229900e+02 9.113000e+01 +0 878 6.290300e+02 8.508997e+01 +4 878 9.303301e+02 2.657800e+02 +0 879 -1.479010e+03 9.223999e+01 +4 879 -1.817200e+02 2.414900e+02 +14 879 -2.480500e+02 1.959700e+02 +16 879 -6.489600e+02 2.473700e+02 +19 879 1.402700e+02 1.211200e+02 +0 880 -1.479010e+03 9.223999e+01 +4 880 -1.817200e+02 2.414900e+02 +14 880 -2.480500e+02 1.959700e+02 +16 880 -6.489600e+02 2.473700e+02 +19 880 1.402700e+02 1.211200e+02 +0 881 8.029500e+02 9.278003e+01 +4 881 1.040820e+03 2.770100e+02 +5 881 6.602800e+02 6.644500e+02 +6 881 -1.814900e+02 -5.634003e+01 +0 882 7.901699e+02 9.503003e+01 +4 882 1.032610e+03 2.783201e+02 +5 882 6.489200e+02 6.654100e+02 +0 883 9.291001e+02 9.937000e+01 +8 883 -6.659998e+01 8.671002e+01 +0 884 7.981299e+02 9.844995e+01 +4 884 1.037900e+03 2.809700e+02 +6 884 -1.865100e+02 -4.857001e+01 +0 885 7.981299e+02 9.844995e+01 +6 885 -1.865100e+02 -4.857001e+01 +0 886 -1.390590e+03 1.066000e+02 +7 886 -1.103300e+03 2.585500e+02 +15 886 5.907500e+02 1.021800e+02 +19 886 2.227600e+02 1.371200e+02 +0 887 1.026120e+03 1.127400e+02 +4 887 1.204240e+03 3.064000e+02 +5 887 8.669199e+02 7.223800e+02 +8 887 1.001000e+02 1.015800e+02 +0 888 1.005390e+03 1.127400e+02 +6 888 5.907996e+01 -6.952002e+01 +0 889 1.266840e+03 1.139301e+02 +8 889 -4.577000e+02 3.376200e+02 +0 890 1.282970e+03 1.173600e+02 +8 890 -4.110800e+02 3.425200e+02 +0 891 -1.388940e+03 1.297800e+02 +4 891 -1.370800e+02 2.616799e+02 +0 892 9.623999e+02 1.311599e+02 +5 892 8.026799e+02 7.246600e+02 +0 893 9.353101e+02 1.323101e+02 +8 893 -5.560999e+01 1.363500e+02 +0 894 1.006550e+03 1.335701e+02 +4 894 1.189720e+03 3.182500e+02 +5 894 8.460601e+02 7.365500e+02 +8 894 6.775000e+01 1.353200e+02 +16 894 6.417800e+02 3.410900e+02 +0 895 1.140880e+03 1.364600e+02 +4 895 1.309810e+03 3.378201e+02 +8 895 2.998000e+02 1.281400e+02 +0 896 -1.402660e+03 1.409900e+02 +4 896 -1.449301e+02 2.673101e+02 +7 896 -1.115770e+03 2.857100e+02 +15 896 5.817000e+02 1.220700e+02 +19 896 2.090601e+02 1.702100e+02 +0 897 1.135420e+03 1.497800e+02 +4 897 1.306440e+03 3.474299e+02 +8 897 2.924800e+02 1.468300e+02 +16 897 7.006500e+02 3.660500e+02 +0 898 1.001140e+03 1.516300e+02 +4 898 1.185530e+03 3.287700e+02 +5 898 8.390400e+02 7.493400e+02 +8 898 5.848999e+01 1.622000e+02 +0 899 -1.388340e+03 1.524500e+02 +4 899 -1.372700e+02 2.731599e+02 +0 900 9.899900e+02 1.642700e+02 +4 900 1.177260e+03 3.360801e+02 +5 900 8.272600e+02 7.566799e+02 +8 900 3.992004e+01 1.843500e+02 +0 901 -1.387580e+03 1.644199e+02 +4 901 -1.375300e+02 2.793201e+02 +7 901 -1.102670e+03 3.041699e+02 +14 901 -2.069400e+02 2.285700e+02 +15 901 5.915699e+02 1.355900e+02 +19 901 2.238199e+02 1.933600e+02 +0 902 5.380901e+02 1.665100e+02 +5 902 4.354200e+02 6.808101e+02 +6 902 -5.599600e+02 1.012100e+02 +0 903 1.097860e+03 1.719399e+02 +4 903 1.279890e+03 3.624800e+02 +8 903 2.392800e+02 1.811700e+02 +0 904 9.963899e+02 1.761599e+02 +8 904 5.252002e+01 2.002200e+02 +16 904 6.368300e+02 3.663000e+02 +0 905 1.593740e+03 1.776899e+02 +5 905 1.205080e+03 8.074000e+02 +6 905 8.774900e+02 3.527002e+01 +7 905 9.203501e+02 3.233500e+02 +0 906 9.359900e+02 1.813000e+02 +8 906 -5.271002e+01 2.120200e+02 +16 906 6.076400e+02 3.639399e+02 +0 907 -1.379770e+03 1.810500e+02 +4 907 -1.345400e+02 2.879600e+02 +5 907 -9.180800e+02 4.541799e+02 +14 907 -2.039600e+02 2.360300e+02 +15 907 5.951500e+02 1.454100e+02 +19 907 2.299700e+02 2.098000e+02 +0 908 9.744299e+02 1.822700e+02 +4 908 1.164920e+03 3.456400e+02 +6 908 3.020996e+01 1.984003e+01 +8 908 1.309998e+01 2.112400e+02 +16 908 6.266801e+02 3.675500e+02 +0 909 9.895601e+02 1.841799e+02 +4 909 1.177940e+03 3.481699e+02 +5 909 8.265500e+02 7.729700e+02 +8 909 4.046997e+01 2.131300e+02 +16 909 6.340000e+02 3.691600e+02 +0 910 7.138799e+02 1.836799e+02 +4 910 9.850801e+02 3.265300e+02 +5 910 5.771200e+02 7.218800e+02 +0 911 7.544099e+02 1.858201e+02 +4 911 1.010720e+03 3.297300e+02 +0 912 6.776599e+02 1.897900e+02 +5 912 5.464301e+02 7.208300e+02 +0 913 6.776599e+02 1.897900e+02 +5 913 5.464100e+02 7.206300e+02 +0 914 -1.685250e+03 2.019800e+02 +4 914 -2.926700e+02 2.965100e+02 +19 914 -6.743994e+01 2.188900e+02 +0 915 -1.718780e+03 2.022000e+02 +4 915 -3.101600e+02 2.960300e+02 +0 916 -9.209700e+02 2.050300e+02 +4 916 8.228003e+01 3.109700e+02 +7 916 -7.925200e+02 3.458500e+02 +14 916 -2.339999e+01 2.439100e+02 +15 916 8.407900e+02 1.705700e+02 +0 917 -1.450760e+03 2.051599e+02 +4 917 -1.699100e+02 2.994500e+02 +14 917 -2.368700e+02 2.475300e+02 +15 917 5.530100e+02 1.587000e+02 +19 917 1.621700e+02 2.305500e+02 +0 918 9.042700e+02 2.055100e+02 +4 918 1.113080e+03 3.531599e+02 +8 918 -1.091100e+02 2.530600e+02 +0 919 -8.275900e+02 2.066000e+02 +4 919 1.226801e+02 3.160701e+02 +19 919 7.081399e+02 2.526200e+02 +0 920 -8.275900e+02 2.066000e+02 +4 920 1.226801e+02 3.160701e+02 +15 920 8.820300e+02 1.757800e+02 +19 920 7.081399e+02 2.526200e+02 +0 921 -9.820900e+02 2.070500e+02 +4 921 5.354004e+01 3.100000e+02 +0 922 6.616201e+02 2.101000e+02 +4 922 9.525100e+02 3.395000e+02 +6 922 -3.675900e+02 1.294800e+02 +0 923 7.996899e+02 2.110801e+02 +4 923 1.040530e+03 3.478201e+02 +5 923 6.458300e+02 7.574800e+02 +0 924 -1.583050e+03 2.152300e+02 +4 924 -2.398300e+02 3.037700e+02 +0 925 -1.133060e+03 2.178101e+02 +4 925 -1.672998e+01 3.112200e+02 +7 925 -9.232400e+02 3.496899e+02 +15 925 7.304200e+02 1.714600e+02 +16 925 -4.706000e+02 3.268500e+02 +19 925 4.531700e+02 2.542300e+02 +0 926 8.696799e+02 2.194099e+02 +4 926 1.089230e+03 3.599800e+02 +0 927 8.696799e+02 2.194099e+02 +4 927 1.089230e+03 3.599800e+02 +5 927 7.076500e+02 7.781400e+02 +6 927 -8.931000e+01 9.034003e+01 +8 927 -1.661300e+02 2.777000e+02 +0 928 -9.273900e+02 2.200000e+02 +4 928 7.865002e+01 3.186599e+02 +14 928 -2.657999e+01 2.506900e+02 +16 928 -3.730500e+02 3.358500e+02 +18 928 -1.320180e+03 3.616003e+01 +0 929 1.531600e+03 2.239299e+02 +8 929 7.722000e+02 2.823900e+02 +0 930 -9.822500e+02 2.250400e+02 +4 930 5.280005e+01 3.196300e+02 +0 931 -1.583550e+03 2.249199e+02 +4 931 -2.397000e+02 3.084900e+02 +15 931 4.718500e+02 1.693000e+02 +19 931 3.151001e+01 2.445000e+02 +0 932 -9.345200e+02 2.258500e+02 +4 932 7.540002e+01 3.216100e+02 +7 932 -8.034500e+02 3.617600e+02 +10 932 -1.215840e+03 -3.528101e+02 +14 932 -2.939001e+01 2.534900e+02 +15 932 8.324399e+02 1.824900e+02 +16 932 -3.770600e+02 3.391600e+02 +19 932 6.239399e+02 2.684500e+02 +0 933 -1.669710e+03 2.269199e+02 +4 933 -2.850000e+02 3.085901e+02 +19 933 -5.269995e+01 2.447400e+02 +0 934 8.887800e+02 2.280500e+02 +4 934 1.102620e+03 3.661799e+02 +5 934 7.241300e+02 7.878400e+02 +8 934 -1.343700e+02 2.884000e+02 +0 935 1.626530e+03 2.288800e+02 +8 935 9.030400e+02 2.904700e+02 +16 935 9.977100e+02 3.732800e+02 +17 935 -8.608000e+02 4.977000e+02 +0 936 6.746399e+02 2.332200e+02 +4 936 9.609600e+02 3.534299e+02 +5 936 5.395699e+02 7.531799e+02 +0 937 -1.068140e+03 2.336400e+02 +4 937 1.400000e+01 3.213000e+02 +7 937 -8.811500e+02 3.635601e+02 +10 937 -1.287140e+03 -3.497500e+02 +14 937 -7.569000e+01 2.579300e+02 +15 937 7.646100e+02 1.828100e+02 +16 937 -4.389400e+02 3.380200e+02 +19 937 5.104000e+02 2.720901e+02 +0 938 -1.238870e+03 2.367100e+02 +4 938 -6.710999e+01 3.190100e+02 +7 938 -9.958200e+02 3.627000e+02 +14 938 -1.434900e+02 2.605800e+02 +15 938 6.726801e+02 1.804800e+02 +16 938 -5.246700e+02 3.347000e+02 +19 938 3.577500e+02 2.691799e+02 +0 939 -1.281530e+03 2.371500e+02 +4 939 -8.818005e+01 3.185601e+02 +19 939 3.171600e+02 2.680901e+02 +0 940 -1.074720e+03 2.402000e+02 +4 940 1.031006e+01 3.247300e+02 +7 940 -8.866700e+02 3.686799e+02 +14 940 -7.906000e+01 2.609300e+02 +15 940 7.601600e+02 1.867800e+02 +16 940 -4.428800e+02 3.418700e+02 +0 941 -1.459370e+03 2.413600e+02 +4 941 -1.751100e+02 3.176599e+02 +14 941 -2.410100e+02 2.642400e+02 +15 941 5.475400e+02 1.790700e+02 +16 941 -6.457100e+02 3.320300e+02 +19 941 1.522300e+02 2.647700e+02 +0 942 -1.199320e+03 2.420200e+02 +4 942 -4.816003e+01 3.225000e+02 +7 942 -9.678100e+02 3.676000e+02 +15 942 6.949500e+02 1.842800e+02 +0 943 -1.623620e+03 2.451599e+02 +4 943 -2.621500e+02 3.189299e+02 +14 943 -3.245500e+02 2.677100e+02 +15 943 4.451400e+02 1.809300e+02 +19 943 -9.949951e+00 2.625000e+02 +0 944 8.576499e+02 2.457100e+02 +4 944 1.081240e+03 3.740200e+02 +5 944 6.948101e+02 7.956700e+02 +8 944 -1.865600e+02 3.188201e+02 +0 945 8.576499e+02 2.457100e+02 +4 945 1.081240e+03 3.740200e+02 +5 945 6.948101e+02 7.956700e+02 +8 945 -1.865600e+02 3.188201e+02 +0 946 1.083160e+03 2.469099e+02 +6 946 1.299700e+02 4.858002e+01 +0 947 7.622400e+02 2.491400e+02 +4 947 1.016600e+03 3.671200e+02 +5 947 6.098500e+02 7.791600e+02 +0 948 -1.237440e+03 2.488301e+02 +4 948 -6.683997e+01 3.250701e+02 +0 949 -1.432060e+03 2.485400e+02 +4 949 -1.626500e+02 3.218201e+02 +14 949 -2.295200e+02 2.675400e+02 +15 949 5.619399e+02 1.842300e+02 +19 949 1.762700e+02 2.733301e+02 +0 950 7.548401e+02 2.507900e+02 +5 950 6.037000e+02 7.794900e+02 +0 951 6.290200e+02 2.508000e+02 +4 951 9.322400e+02 3.602800e+02 +7 951 2.797700e+02 3.877700e+02 +10 951 -2.152600e+02 -3.439200e+02 +11 951 3.597100e+02 2.131800e+02 +12 951 -8.328300e+02 -4.497600e+02 +13 951 -1.650130e+03 7.100900e+02 +18 951 -4.506700e+02 5.597998e+01 +20 951 -3.820000e+02 -1.495200e+02 +0 952 -1.533360e+03 2.509399e+02 +4 952 -2.115500e+02 3.213800e+02 +15 952 5.064399e+02 1.836500e+02 +16 952 -6.872100e+02 3.355300e+02 +19 952 8.456006e+01 2.721400e+02 +0 953 -1.662700e+03 2.519700e+02 +4 953 -2.825200e+02 3.220200e+02 +5 953 -1.127450e+03 4.687300e+02 +0 954 -1.358840e+03 2.526799e+02 +4 954 -1.257900e+02 3.247800e+02 +7 954 -1.087160e+03 3.739399e+02 +19 954 2.465400e+02 2.798600e+02 +0 955 -1.368710e+03 2.536500e+02 +4 955 -1.299200e+02 3.250901e+02 +7 955 -1.093130e+03 3.748800e+02 +15 955 6.006100e+02 1.874900e+02 +19 955 2.373600e+02 2.807700e+02 +0 956 -1.590070e+03 2.537900e+02 +4 956 -2.445000e+02 3.233700e+02 +5 956 -1.076420e+03 4.788201e+02 +14 956 -3.067200e+02 2.712900e+02 +15 956 4.659600e+02 1.859600e+02 +16 956 -7.297100e+02 3.367800e+02 +0 957 -1.383100e+03 2.555901e+02 +4 957 -1.375699e+02 3.257700e+02 +19 957 2.247100e+02 2.822500e+02 +0 958 5.589800e+02 2.635901e+02 +4 958 8.897600e+02 3.640801e+02 +7 958 2.440300e+02 3.937800e+02 +0 959 5.589800e+02 2.635901e+02 +7 959 2.440300e+02 3.937800e+02 +0 960 -1.377030e+03 2.742300e+02 +4 960 -1.347000e+02 3.356300e+02 +7 960 -1.100980e+03 3.910200e+02 +15 960 5.954500e+02 1.996500e+02 +16 960 -6.011600e+02 3.521100e+02 +19 960 2.292000e+02 3.006500e+02 +0 961 -1.592370e+03 2.781100e+02 +4 961 -2.466801e+02 3.358800e+02 +0 962 6.821101e+02 2.811500e+02 +4 962 9.657100e+02 3.815901e+02 +5 962 5.401500e+02 7.904000e+02 +6 962 -3.308000e+02 2.235800e+02 +0 963 -8.929400e+02 2.849900e+02 +4 963 9.288000e+01 3.548900e+02 +15 963 8.508700e+02 2.207200e+02 +19 963 6.546599e+02 3.290801e+02 +0 964 -1.376590e+03 2.858401e+02 +4 964 -1.353199e+02 3.415400e+02 +7 964 -1.101540e+03 4.004500e+02 +16 964 -6.019000e+02 3.585601e+02 +19 964 2.289100e+02 3.118600e+02 +0 965 -1.604510e+03 2.903401e+02 +4 965 -2.530500e+02 3.419500e+02 +14 965 -3.148600e+02 2.883400e+02 +16 965 -7.390000e+02 3.574500e+02 +19 965 6.770020e+00 3.064500e+02 +0 966 -1.604510e+03 2.903401e+02 +4 966 -2.530500e+02 3.419500e+02 +14 966 -3.148600e+02 2.883400e+02 +19 966 6.770020e+00 3.064500e+02 +0 967 -8.897500e+02 2.911500e+02 +4 967 9.406995e+01 3.583101e+02 +0 968 -8.692900e+02 2.927900e+02 +4 968 1.029700e+02 3.601799e+02 +14 968 -9.940002e+00 2.839700e+02 +15 968 8.619800e+02 2.266600e+02 +0 969 6.226001e+02 3.012300e+02 +4 969 9.287500e+02 3.881300e+02 +5 969 4.897800e+02 7.951300e+02 +7 969 2.765300e+02 4.228201e+02 +0 970 -1.532320e+03 3.027400e+02 +4 970 -2.125200e+02 3.479600e+02 +14 970 -2.747200e+02 2.934100e+02 +19 970 8.293005e+01 3.217300e+02 +0 971 -1.590560e+03 3.029000e+02 +4 971 -2.457100e+02 3.485901e+02 +5 971 -1.083870e+03 5.134500e+02 +15 971 4.650800e+02 2.142200e+02 +16 971 -7.317300e+02 3.650900e+02 +19 971 2.050000e+01 3.191899e+02 +0 972 -1.383950e+03 3.052400e+02 +4 972 -1.392800e+02 3.512700e+02 +5 972 -9.409600e+02 5.400300e+02 +7 972 -1.106950e+03 4.153600e+02 +15 972 5.905800e+02 2.174400e+02 +16 972 -6.059100e+02 3.694500e+02 +19 972 2.220699e+02 3.305500e+02 +0 973 -1.383950e+03 3.052400e+02 +4 973 -1.392800e+02 3.512700e+02 +5 973 -9.409600e+02 5.400300e+02 +7 973 -1.106950e+03 4.153600e+02 +15 973 5.905800e+02 2.174400e+02 +16 973 -6.059100e+02 3.694500e+02 +19 973 2.220699e+02 3.305500e+02 +0 974 6.142200e+02 3.060300e+02 +4 974 9.240801e+02 3.903600e+02 +0 975 1.598850e+03 3.109399e+02 +2 975 7.826899e+02 2.005100e+02 +7 975 9.255100e+02 4.102500e+02 +8 975 8.641000e+02 4.137800e+02 +17 975 -9.132900e+02 6.285701e+02 +0 976 -1.375640e+03 3.114700e+02 +4 976 -1.352000e+02 3.546200e+02 +7 976 -1.101060e+03 4.207400e+02 +14 976 -2.028100e+02 2.963300e+02 +15 976 5.954399e+02 2.214500e+02 +19 976 2.288400e+02 3.370000e+02 +0 977 5.841001e+02 3.148600e+02 +4 977 9.060200e+02 3.936699e+02 +0 978 5.841001e+02 3.148600e+02 +4 978 9.060200e+02 3.936699e+02 +0 979 -1.591300e+03 3.153401e+02 +4 979 -2.467600e+02 3.549099e+02 +5 979 -1.087360e+03 5.219800e+02 +15 979 4.642300e+02 2.213300e+02 +16 979 -7.323200e+02 3.719700e+02 +19 979 1.918005e+01 3.309000e+02 +0 980 -1.604500e+03 3.150901e+02 +4 980 -2.534100e+02 3.547600e+02 +5 980 -1.096880e+03 5.199299e+02 +15 980 4.560000e+02 2.210000e+02 +19 980 6.339966e+00 3.300901e+02 +0 981 -1.146450e+03 3.243101e+02 +4 981 -2.492004e+01 3.666599e+02 +15 981 7.213300e+02 2.347200e+02 +0 982 -1.146450e+03 3.243101e+02 +4 982 -2.492004e+01 3.666599e+02 +0 983 1.590790e+03 3.292900e+02 +2 983 7.755300e+02 2.193800e+02 +12 983 -2.086200e+02 -4.289800e+02 +17 983 -9.225400e+02 6.585400e+02 +0 984 8.405200e+02 3.294500e+02 +8 984 -2.143700e+02 4.491400e+02 +0 985 -1.347480e+03 3.351699e+02 +4 985 -1.223000e+02 3.677900e+02 +0 986 -9.217300e+02 3.395400e+02 +4 986 7.955005e+01 3.824900e+02 +14 986 -2.459000e+01 3.053700e+02 +15 986 8.374700e+02 2.525900e+02 +16 986 -3.743800e+02 4.042900e+02 +0 987 1.638310e+03 3.406500e+02 +7 987 9.502600e+02 4.286000e+02 +0 988 1.516270e+03 3.436799e+02 +8 988 7.523600e+02 4.635500e+02 +0 989 -1.065220e+03 3.566400e+02 +4 989 1.320996e+01 3.858900e+02 +10 989 -1.282500e+03 -2.565400e+02 +15 989 7.649200e+02 2.566400e+02 +20 989 -1.187470e+03 -9.626001e+01 +0 990 -1.065220e+03 3.566400e+02 +7 990 -8.826500e+02 4.598600e+02 +15 990 7.649200e+02 2.566400e+02 +19 990 5.092500e+02 3.946599e+02 +0 991 -1.128250e+03 3.564500e+02 +4 991 -1.645996e+01 3.840100e+02 +5 991 -7.759300e+02 6.104100e+02 +7 991 -9.237900e+02 4.585601e+02 +14 991 -9.862000e+01 3.148100e+02 +15 991 7.317400e+02 2.543400e+02 +19 991 4.530500e+02 3.916899e+02 +0 992 -1.076040e+03 3.575400e+02 +4 992 7.479980e+00 3.860601e+02 +16 992 -4.483500e+02 4.082700e+02 +0 993 -1.667710e+03 3.660100e+02 +4 993 -2.868400e+02 3.803301e+02 +5 993 -1.148670e+03 5.481200e+02 +0 994 -1.667710e+03 3.660100e+02 +4 994 -2.868400e+02 3.803301e+02 +19 994 -5.445996e+01 3.758800e+02 +0 995 -1.294960e+03 3.668700e+02 +4 995 -9.656006e+01 3.849099e+02 +5 995 -8.894600e+02 5.955701e+02 +7 995 -1.041450e+03 4.647200e+02 +14 995 -1.674200e+02 3.212400e+02 +15 995 6.400200e+02 2.555701e+02 +16 995 -5.592100e+02 4.065900e+02 +19 995 3.018700e+02 3.943301e+02 +0 996 -1.570070e+03 3.667800e+02 +4 996 -2.367000e+02 3.814700e+02 +5 996 -1.080440e+03 5.607600e+02 +14 996 -2.976000e+02 3.236000e+02 +15 996 4.762000e+02 2.511400e+02 +16 996 -7.210500e+02 4.016300e+02 +19 996 3.846997e+01 3.814000e+02 +0 997 5.775200e+02 3.688600e+02 +5 997 4.468000e+02 8.395800e+02 +8 997 -6.753500e+02 5.379399e+02 +0 998 -1.225760e+03 3.694000e+02 +4 998 -6.338000e+01 3.877200e+02 +14 998 -1.380000e+02 3.215100e+02 +15 998 6.781801e+02 2.589200e+02 +16 998 -5.230500e+02 4.099700e+02 +19 998 3.650000e+02 4.000100e+02 +0 999 -1.225760e+03 3.694000e+02 +4 999 -6.338000e+01 3.877200e+02 +7 999 -9.912200e+02 4.672300e+02 +14 999 -1.380000e+02 3.215100e+02 +15 999 6.781801e+02 2.589200e+02 +16 999 -5.230500e+02 4.099700e+02 +19 999 3.650000e+02 4.000100e+02 +0 1000 -1.415320e+03 3.699600e+02 +4 1000 -1.561000e+02 3.843600e+02 +5 1000 -9.721200e+02 5.820100e+02 +14 1000 -2.212600e+02 3.235700e+02 +15 1000 5.708900e+02 2.549400e+02 +16 1000 -6.265400e+02 4.057300e+02 +19 1000 1.893400e+02 3.919399e+02 +0 1001 -1.219890e+03 3.753500e+02 +4 1001 -6.023999e+01 3.910000e+02 +7 1001 -9.867800e+02 4.721000e+02 +15 1001 6.816400e+02 2.626899e+02 +16 1001 -5.198600e+02 4.132100e+02 +19 1001 3.694500e+02 4.052500e+02 +0 1002 4.566599e+02 3.765000e+02 +2 1002 -3.736900e+02 3.196100e+02 +6 1002 -6.637500e+02 4.208201e+02 +7 1002 1.824000e+02 4.718500e+02 +9 1002 -3.934301e+02 3.800400e+02 +18 1002 -5.171700e+02 1.206799e+02 +0 1003 -1.415780e+03 3.818800e+02 +4 1003 -1.573900e+02 3.916500e+02 +0 1004 -8.128000e+02 3.912700e+02 +4 1004 1.269399e+02 4.163000e+02 +0 1005 -1.373430e+03 3.956899e+02 +4 1005 -1.356200e+02 3.982900e+02 +0 1006 6.218601e+02 4.010000e+02 +5 1006 4.788700e+02 8.721300e+02 +0 1007 -1.373320e+03 4.086500e+02 +4 1007 -1.358500e+02 4.047800e+02 +14 1007 -2.016800e+02 3.413000e+02 +15 1007 5.953700e+02 2.779399e+02 +16 1007 -6.047900e+02 4.285500e+02 +19 1007 2.279700e+02 4.317600e+02 +0 1008 1.653010e+03 4.111699e+02 +7 1008 9.489900e+02 4.883000e+02 +8 1008 9.508101e+02 5.536500e+02 +12 1008 -1.882400e+02 -3.618800e+02 +0 1009 5.547300e+02 4.120200e+02 +5 1009 4.240000e+02 8.679600e+02 +0 1010 6.176101e+02 4.143201e+02 +4 1010 9.278201e+02 4.543700e+02 +0 1011 5.301399e+02 4.230000e+02 +4 1011 8.748999e+02 4.526899e+02 +5 1011 4.048700e+02 8.716600e+02 +8 1011 -7.556000e+02 6.305701e+02 +0 1012 -1.372420e+03 4.234800e+02 +4 1012 -1.362200e+02 4.126400e+02 +14 1012 -2.016100e+02 3.482400e+02 +15 1012 5.954100e+02 2.866100e+02 +0 1013 5.754500e+02 4.245901e+02 +4 1013 9.022100e+02 4.571300e+02 +8 1013 -6.771000e+02 6.283700e+02 +0 1014 4.874299e+02 4.250100e+02 +4 1014 8.502800e+02 4.528000e+02 +0 1015 4.426201e+02 4.324399e+02 +4 1015 8.236399e+02 4.554700e+02 +10 1015 -3.022300e+02 -2.306400e+02 +12 1015 -9.298300e+02 -3.273700e+02 +0 1016 5.467000e+02 4.341200e+02 +4 1016 8.847800e+02 4.604800e+02 +8 1016 -7.278500e+02 6.467600e+02 +0 1017 -8.187300e+02 4.401300e+02 +4 1017 1.235100e+02 4.424800e+02 +10 1017 -1.162420e+03 -1.882800e+02 +15 1017 8.841300e+02 3.203700e+02 +19 1017 7.082300e+02 4.890701e+02 +0 1018 5.088101e+02 4.412600e+02 +4 1018 8.626101e+02 4.627600e+02 +8 1018 -7.926700e+02 6.614000e+02 +0 1019 4.910601e+02 4.463000e+02 +4 1019 8.518799e+02 4.650300e+02 +0 1020 -1.370210e+03 4.510000e+02 +4 1020 -1.354200e+02 4.269600e+02 +0 1021 -8.932700e+02 4.520701e+02 +4 1021 9.059998e+01 4.440200e+02 +15 1021 8.493300e+02 3.230800e+02 +19 1021 6.489700e+02 4.987700e+02 +0 1022 -9.224500e+02 4.575601e+02 +4 1022 7.708997e+01 4.454700e+02 +0 1023 -9.224500e+02 4.575601e+02 +4 1023 7.708997e+01 4.454700e+02 +10 1023 -1.205120e+03 -1.789301e+02 +15 1023 8.351400e+02 3.245400e+02 +18 1023 -1.320390e+03 1.942900e+02 +0 1024 -9.288500e+02 4.652300e+02 +4 1024 7.433997e+01 4.493600e+02 +7 1024 -8.071000e+02 5.503101e+02 +10 1024 -1.207760e+03 -1.730400e+02 +14 1024 -2.695001e+01 3.633100e+02 +15 1024 8.316300e+02 3.290601e+02 +16 1024 -3.823900e+02 4.759200e+02 +18 1024 -1.323120e+03 1.991799e+02 +19 1024 6.208300e+02 5.098800e+02 +20 1024 -1.136150e+03 -2.893994e+01 +0 1025 5.305300e+02 4.697900e+02 +5 1025 4.006400e+02 9.088300e+02 +0 1026 4.805701e+02 4.730200e+02 +5 1026 3.624800e+02 9.039000e+02 +0 1027 -1.062070e+03 4.787300e+02 +4 1027 1.218005e+01 4.504399e+02 +10 1027 -1.279210e+03 -1.650100e+02 +15 1027 7.638600e+02 3.299900e+02 +16 1027 -4.454200e+02 4.778201e+02 +0 1028 -7.451800e+02 4.800400e+02 +4 1028 1.533900e+02 4.714199e+02 +0 1029 -1.228040e+03 4.882800e+02 +4 1029 -6.698999e+01 4.499600e+02 +7 1029 -9.990400e+02 5.623500e+02 +10 1029 -1.385850e+03 -1.559100e+02 +14 1029 -1.402300e+02 3.769900e+02 +15 1029 6.742000e+02 3.297300e+02 +16 1029 -5.300600e+02 4.781200e+02 +19 1029 3.571801e+02 5.173301e+02 +0 1030 -1.133210e+03 4.917200e+02 +4 1030 -2.217004e+01 4.546599e+02 +7 1030 -9.345900e+02 5.657200e+02 +10 1030 -1.323420e+03 -1.542300e+02 +14 1030 -1.021800e+02 3.775000e+02 +19 1030 4.415100e+02 5.253201e+02 +0 1031 -1.651940e+03 5.025000e+02 +4 1031 -2.828700e+02 4.508800e+02 +0 1032 -1.281910e+03 5.037400e+02 +4 1032 -9.413000e+01 4.564600e+02 +14 1032 -1.635200e+02 3.844200e+02 +0 1033 -1.295700e+03 5.046100e+02 +4 1033 -1.010100e+02 4.566599e+02 +5 1033 -9.126700e+02 6.939800e+02 +10 1033 -1.435280e+03 -1.411100e+02 +14 1033 -1.697400e+02 3.852400e+02 +16 1033 -5.680500e+02 4.855400e+02 +19 1033 2.926000e+02 5.294000e+02 +0 1034 -1.584930e+03 5.053000e+02 +4 1034 -2.475800e+02 4.530000e+02 +5 1034 -1.114470e+03 6.576799e+02 +15 1034 4.646300e+02 3.309200e+02 +16 1034 -7.375900e+02 4.819800e+02 +0 1035 -7.899400e+02 5.196599e+02 +4 1035 1.354900e+02 4.886000e+02 +15 1035 8.963800e+02 3.729200e+02 +19 1035 7.282100e+02 5.715000e+02 +0 1036 -1.033200e+03 5.225100e+02 +4 1036 2.479004e+01 4.749299e+02 +7 1036 -8.701400e+02 5.920800e+02 +19 1036 5.298000e+02 5.619700e+02 +0 1037 -1.367790e+03 5.262100e+02 +4 1037 -1.361801e+02 4.658900e+02 +15 1037 5.956899e+02 3.468101e+02 +0 1038 -1.075590e+03 5.270300e+02 +4 1038 3.819946e+00 4.759900e+02 +19 1038 4.909100e+02 5.639200e+02 +0 1039 -1.075590e+03 5.270300e+02 +4 1039 3.819946e+00 4.759900e+02 +16 1039 -4.554600e+02 5.050400e+02 +19 1039 4.909100e+02 5.639200e+02 +0 1040 -1.366060e+03 5.470000e+02 +4 1040 -1.357100e+02 4.768401e+02 +14 1040 -1.998400e+02 4.056700e+02 +0 1041 -8.924200e+02 5.488201e+02 +4 1041 8.975000e+01 4.959399e+02 +7 1041 -7.878200e+02 6.181899e+02 +14 1041 -1.384000e+01 4.020100e+02 +15 1041 8.491500e+02 3.819800e+02 +19 1041 6.487200e+02 5.959900e+02 +0 1042 -1.155270e+03 5.527600e+02 +4 1042 -3.419995e+01 4.867000e+02 +7 1042 -9.527100e+02 6.152000e+02 +19 1042 4.182500e+02 5.849399e+02 +0 1043 -1.623380e+03 5.761899e+02 +4 1043 -2.698900e+02 4.893300e+02 +0 1044 -1.623380e+03 5.761899e+02 +4 1044 -2.698900e+02 4.893300e+02 +0 1045 -1.604550e+03 5.768500e+02 +4 1045 -2.598500e+02 4.901000e+02 +5 1045 -1.140320e+03 7.069200e+02 +15 1045 4.515000e+02 3.722900e+02 +16 1045 -7.534700e+02 5.234800e+02 +0 1046 -1.034810e+03 5.999800e+02 +4 1046 2.441003e+01 5.149200e+02 +7 1046 -8.671000e+02 6.523900e+02 +19 1046 5.299600e+02 6.397900e+02 +0 1047 -8.055200e+02 6.291899e+02 +4 1047 1.261700e+02 5.474000e+02 +15 1047 8.860900e+02 4.397200e+02 +0 1048 -8.111500e+02 6.370100e+02 +4 1048 1.237400e+02 5.510300e+02 +7 1048 -7.543600e+02 6.948400e+02 +10 1048 -1.155350e+03 -4.102002e+01 +14 1048 8.269989e+00 4.420900e+02 +15 1048 8.836500e+02 4.437800e+02 +16 1048 -3.400700e+02 5.835300e+02 +19 1048 7.058301e+02 6.907400e+02 +0 1049 -8.518300e+02 6.498900e+02 +4 1049 1.053500e+02 5.545400e+02 +0 1050 -1.267030e+03 6.499800e+02 +4 1050 -9.031995e+01 5.323000e+02 +15 1050 6.477200e+02 4.221799e+02 +0 1051 -1.192230e+03 6.534000e+02 +4 1051 -5.294995e+01 5.381500e+02 +7 1051 -9.791300e+02 6.946000e+02 +14 1051 -1.254500e+02 4.533101e+02 +15 1051 6.905601e+02 4.285900e+02 +0 1052 -1.558230e+03 6.554200e+02 +4 1052 -2.380400e+02 5.312700e+02 +5 1052 -1.119920e+03 7.690900e+02 +15 1052 4.766700e+02 4.181799e+02 +16 1052 -7.287500e+02 5.697600e+02 +0 1053 -8.081000e+02 6.743500e+02 +4 1053 1.236700e+02 5.727000e+02 +7 1053 -7.559600e+02 7.260900e+02 +14 1053 8.290009e+00 4.594800e+02 +15 1053 8.830500e+02 4.679700e+02 +16 1053 -3.405300e+02 6.053600e+02 +0 1054 -8.081000e+02 6.743500e+02 +4 1054 1.236700e+02 5.727000e+02 +7 1054 -7.559600e+02 7.260900e+02 +10 1054 -1.154860e+03 -1.228003e+01 +15 1054 8.830500e+02 4.679700e+02 +16 1054 -3.405300e+02 6.053600e+02 +19 1054 7.047500e+02 7.287800e+02 +0 1055 -1.052050e+03 6.898400e+02 +4 1055 1.235999e+01 5.637900e+02 +0 1056 -9.348300e+02 7.076600e+02 +4 1056 6.581995e+01 5.810400e+02 +7 1056 -8.218200e+02 7.453000e+02 +10 1056 -1.208250e+03 8.439941e+00 +15 1056 8.216801e+02 4.778000e+02 +16 1056 -3.962300e+02 6.171200e+02 +0 1057 -1.182440e+03 7.079500e+02 +4 1057 -4.998999e+01 5.678000e+02 +5 1057 -8.671500e+02 8.578000e+02 +7 1057 -9.744300e+02 7.387700e+02 +15 1057 6.944600e+02 4.620601e+02 +19 1057 3.901700e+02 7.369000e+02 +0 1058 -9.132000e+02 7.095400e+02 +4 1058 7.615002e+01 5.826400e+02 +15 1058 8.332600e+02 4.800200e+02 +19 1058 6.214399e+02 7.551600e+02 +0 1059 -1.213910e+03 7.111500e+02 +4 1059 -6.431006e+01 5.684800e+02 +5 1059 -8.884300e+02 8.556200e+02 +0 1060 -1.045110e+03 7.478000e+02 +4 1060 1.443005e+01 5.953201e+02 +7 1060 -8.859200e+02 7.740900e+02 +19 1060 5.084500e+02 7.878000e+02 +0 1061 -1.268510e+03 7.560701e+02 +4 1061 -9.383997e+01 5.902900e+02 +10 1061 -1.409150e+03 4.898999e+01 +15 1061 6.447700e+02 4.860900e+02 +19 1061 3.078000e+02 7.780601e+02 +20 1061 -1.287010e+03 1.364399e+02 +0 1062 -1.268510e+03 7.560701e+02 +4 1062 -9.383997e+01 5.902900e+02 +5 1062 -9.342800e+02 8.812900e+02 +10 1062 -1.409150e+03 4.898999e+01 +15 1062 6.447700e+02 4.860900e+02 +16 1062 -5.636200e+02 6.320800e+02 +20 1062 -1.287010e+03 1.364399e+02 +0 1063 -1.524020e+03 8.324600e+02 +4 1063 -2.262300e+02 6.254700e+02 +0 1064 -1.437610e+03 8.352000e+02 +4 1064 -1.811899e+02 6.283300e+02 +5 1064 -1.066140e+03 9.170000e+02 +15 1064 5.428800e+02 5.269700e+02 +19 1064 1.441500e+02 8.418400e+02 +0 1065 -1.559780e+03 8.470800e+02 +4 1065 -2.460601e+02 6.349000e+02 +5 1065 -1.157020e+03 9.126100e+02 +14 1065 -3.004400e+02 5.506400e+02 +15 1065 4.662000e+02 5.325800e+02 +0 1066 -1.515600e+03 8.521000e+02 +4 1066 -2.219200e+02 6.360900e+02 +14 1066 -2.769100e+02 5.521000e+02 +0 1067 -1.430630e+03 8.547200e+02 +4 1067 -1.777400e+02 6.387500e+02 +14 1067 -2.350800e+02 5.520900e+02 +15 1067 5.466801e+02 5.389100e+02 +16 1067 -6.631500e+02 6.884301e+02 +19 1067 1.490000e+02 8.612800e+02 +0 1068 -1.520460e+03 8.578000e+02 +4 1068 -2.254900e+02 6.386600e+02 +5 1068 -1.128800e+03 9.228500e+02 +14 1068 -2.787700e+02 5.548400e+02 +19 1068 6.408997e+01 8.564800e+02 +0 1069 -1.520460e+03 8.578000e+02 +4 1069 -2.254900e+02 6.386600e+02 +5 1069 -1.128800e+03 9.228500e+02 +14 1069 -2.787700e+02 5.548400e+02 +19 1069 6.408997e+01 8.564800e+02 +0 1070 -1.468210e+03 8.661899e+02 +4 1070 -1.974900e+02 6.437600e+02 +5 1070 -1.092060e+03 9.357600e+02 +14 1070 -2.533400e+02 5.580200e+02 +15 1070 5.241600e+02 5.439600e+02 +19 1070 1.128600e+02 8.691000e+02 +20 1070 -1.413440e+03 2.123401e+02 +0 1071 -1.468210e+03 8.661899e+02 +4 1071 -1.974900e+02 6.437600e+02 +5 1071 -1.092060e+03 9.357600e+02 +14 1071 -2.533400e+02 5.580200e+02 +15 1071 5.241600e+02 5.439600e+02 +19 1071 1.128600e+02 8.691000e+02 +20 1071 -1.413440e+03 2.123401e+02 +0 1072 -1.448050e+03 8.748600e+02 +4 1072 -1.867100e+02 6.486100e+02 +5 1072 -1.079000e+03 9.445100e+02 +15 1072 5.357300e+02 5.494700e+02 +0 1073 -1.401140e+03 8.825900e+02 +4 1073 -1.622300e+02 6.526300e+02 +16 1073 -6.439400e+02 7.041300e+02 +19 1073 1.795699e+02 8.909200e+02 +0 1074 -1.239970e+03 9.616599e+02 +4 1074 -1.126100e+02 7.207900e+02 +0 1075 7.617400e+02 -7.939001e+01 +4 1075 1.011370e+03 1.754700e+02 +0 1076 7.670701e+02 -6.578003e+01 +4 1076 1.014790e+03 1.835500e+02 +0 1077 7.859199e+02 1.271997e+01 +4 1077 1.028580e+03 2.299000e+02 +0 1078 8.455500e+02 2.818994e+01 +5 1078 7.041700e+02 6.233700e+02 +6 1078 -1.307700e+02 -1.485500e+02 +8 1078 -2.106000e+02 -2.121002e+01 +0 1079 7.901399e+02 4.570996e+01 +4 1079 1.031870e+03 2.494199e+02 +0 1080 -9.918800e+02 5.353003e+01 +4 1080 5.173999e+01 2.296400e+02 +7 1080 -8.293400e+02 2.255100e+02 +10 1080 -1.246820e+03 -4.846100e+02 +15 1080 8.061000e+02 7.685999e+01 +0 1081 6.728999e+02 5.797998e+01 +4 1081 9.573000e+02 2.529700e+02 +0 1082 -9.965300e+02 5.825000e+01 +4 1082 4.906006e+01 2.321599e+02 +0 1083 -1.447540e+03 6.614001e+01 +4 1083 -1.655800e+02 2.288600e+02 +15 1083 5.573800e+02 7.835999e+01 +16 1083 -6.306700e+02 2.334000e+02 +19 1083 1.688900e+02 9.612000e+01 +0 1084 9.256201e+02 7.164001e+01 +8 1084 -7.256000e+01 4.251001e+01 +0 1085 6.284099e+02 7.438000e+01 +2 1085 -2.417000e+02 -3.332001e+01 +4 1085 9.299500e+02 2.595801e+02 +7 1085 2.804200e+02 2.610100e+02 +9 1085 -2.824800e+02 1.164800e+02 +10 1085 -2.134500e+02 -4.583800e+02 +11 1085 3.631000e+02 5.790002e+01 +13 1085 -1.650610e+03 1.878800e+02 +18 1085 -4.506700e+02 -4.421997e+01 +0 1086 5.896101e+02 7.423999e+01 +4 1086 9.066599e+02 2.576300e+02 +5 1086 4.860200e+02 6.196799e+02 +0 1087 8.662100e+02 7.738000e+01 +4 1087 1.085190e+03 2.731799e+02 +8 1087 -1.715600e+02 5.477002e+01 +0 1088 9.228999e+02 7.825000e+01 +4 1088 1.124060e+03 2.764399e+02 +8 1088 -7.707001e+01 5.429999e+01 +0 1089 6.230400e+02 7.800000e+01 +4 1089 9.268201e+02 2.617000e+02 +5 1089 5.127700e+02 6.275000e+02 +0 1090 1.093110e+03 7.957996e+01 +4 1090 1.259080e+03 2.910000e+02 +8 1090 2.128900e+02 4.791998e+01 +0 1091 8.620801e+02 8.145996e+01 +4 1091 1.082200e+03 2.753101e+02 +8 1091 -1.786300e+02 6.116998e+01 +0 1092 -1.072420e+03 8.079004e+01 +4 1092 1.414001e+01 2.419099e+02 +7 1092 -8.785600e+02 2.445801e+02 +15 1092 7.646200e+02 9.148999e+01 +0 1093 9.135701e+02 8.322998e+01 +5 1093 7.594299e+02 6.776799e+02 +8 1093 -9.415997e+01 6.271997e+01 +0 1094 8.331899e+02 8.629004e+01 +4 1094 1.062610e+03 2.762800e+02 +6 1094 -1.422600e+02 -7.258002e+01 +0 1095 7.103401e+02 8.952002e+01 +4 1095 9.814099e+02 2.723000e+02 +0 1096 8.508301e+02 9.193005e+01 +4 1096 1.074260e+03 2.809099e+02 +0 1097 1.026330e+03 9.447998e+01 +4 1097 1.204180e+03 2.948900e+02 +5 1097 8.691201e+02 7.080100e+02 +8 1097 1.007100e+02 7.371997e+01 +0 1098 1.000570e+03 1.007800e+02 +4 1098 1.183900e+03 2.964500e+02 +8 1098 5.714001e+01 8.456000e+01 +0 1099 7.458701e+02 1.016801e+02 +4 1099 1.004630e+03 2.805601e+02 +0 1100 9.558401e+02 1.030500e+02 +4 1100 1.149510e+03 2.945901e+02 +8 1100 -1.869000e+01 9.008002e+01 +0 1101 8.025701e+02 1.028101e+02 +4 1101 1.041070e+03 2.834700e+02 +6 1101 -1.801600e+02 -4.526001e+01 +0 1102 5.721699e+02 1.093600e+02 +4 1102 8.958999e+02 2.770400e+02 +0 1103 9.641201e+02 1.102400e+02 +5 1103 8.066201e+02 7.084600e+02 +8 1103 -5.340027e+00 1.012800e+02 +0 1104 9.018000e+02 1.117400e+02 +8 1104 -1.144200e+02 1.077600e+02 +0 1105 7.853101e+02 1.162500e+02 +5 1105 6.421801e+02 6.814399e+02 +0 1106 -1.546130e+03 1.170300e+02 +4 1106 -2.175100e+02 2.546599e+02 +5 1106 -1.023170e+03 3.891300e+02 +16 1106 -6.926700e+02 2.616000e+02 +0 1107 9.915200e+02 1.231200e+02 +8 1107 4.215002e+01 1.191300e+02 +0 1108 6.498799e+02 1.281300e+02 +4 1108 9.437400e+02 2.915300e+02 +5 1108 5.290400e+02 6.701100e+02 +0 1109 5.743701e+02 1.319600e+02 +4 1109 8.979700e+02 2.901100e+02 +0 1110 8.384099e+02 1.354000e+02 +4 1110 1.066110e+03 3.061899e+02 +5 1110 6.882900e+02 7.053800e+02 +0 1111 9.961499e+02 1.358700e+02 +5 1111 8.360200e+02 7.359700e+02 +8 1111 5.093994e+01 1.385600e+02 +16 1111 6.360400e+02 3.426600e+02 +0 1112 -1.381230e+03 1.356200e+02 +4 1112 -1.345400e+02 2.647400e+02 +19 1112 2.300200e+02 1.656599e+02 +0 1113 9.429199e+02 1.365801e+02 +4 1113 1.140200e+03 3.139399e+02 +8 1113 -4.227002e+01 1.430500e+02 +16 1113 6.127100e+02 3.384600e+02 +0 1114 9.961399e+02 1.445200e+02 +4 1114 1.181900e+03 3.241100e+02 +8 1114 5.062000e+01 1.518500e+02 +0 1115 9.598701e+02 1.461699e+02 +8 1115 -1.145001e+01 1.570100e+02 +0 1116 9.596799e+02 1.560601e+02 +4 1116 1.153970e+03 3.281000e+02 +5 1116 7.983501e+02 7.446200e+02 +8 1116 -1.178998e+01 1.714300e+02 +0 1117 7.996899e+02 1.579600e+02 +4 1117 1.039980e+03 3.164800e+02 +0 1118 8.981399e+02 1.641300e+02 +5 1118 7.387900e+02 7.385300e+02 +0 1119 6.060300e+02 1.652500e+02 +5 1119 4.905200e+02 6.899700e+02 +0 1120 6.060300e+02 1.652500e+02 +5 1120 4.905200e+02 6.899700e+02 +0 1121 1.003280e+03 1.670400e+02 +4 1121 1.188390e+03 3.382100e+02 +0 1122 8.700901e+02 1.671000e+02 +8 1122 -1.667600e+02 1.948200e+02 +0 1123 1.513030e+03 1.682200e+02 +7 1123 8.666499e+02 3.205801e+02 +8 1123 7.483600e+02 1.978600e+02 +0 1124 9.110500e+02 1.707500e+02 +8 1124 -9.804999e+01 1.981200e+02 +0 1125 9.384099e+02 1.737100e+02 +5 1125 7.750500e+02 7.536000e+02 +0 1126 7.902700e+02 1.738600e+02 +4 1126 1.033950e+03 3.250200e+02 +5 1126 6.411400e+02 7.263500e+02 +0 1127 8.864900e+02 1.778700e+02 +5 1127 7.277100e+02 7.472800e+02 +8 1127 -1.370500e+02 2.089900e+02 +0 1128 7.053799e+02 1.782300e+02 +4 1128 9.793000e+02 3.234299e+02 +0 1129 8.815100e+02 1.813500e+02 +4 1129 1.096870e+03 3.370000e+02 +0 1130 8.815100e+02 1.813500e+02 +4 1130 1.096870e+03 3.370000e+02 +0 1131 5.809199e+02 1.826200e+02 +4 1131 9.023799e+02 3.188301e+02 +6 1131 -4.902000e+02 1.130200e+02 +0 1132 9.622500e+02 1.846500e+02 +4 1132 1.156580e+03 3.457500e+02 +6 1132 1.627002e+01 2.346002e+01 +8 1132 -6.630005e+00 2.155300e+02 +0 1133 6.874600e+02 1.850400e+02 +5 1133 5.534500e+02 7.177200e+02 +0 1134 6.689099e+02 1.846400e+02 +4 1134 9.563501e+02 3.248401e+02 +5 1134 5.401400e+02 7.150300e+02 +0 1135 -1.594460e+03 1.850300e+02 +4 1135 -2.449399e+02 2.884700e+02 +14 1135 -3.085700e+02 2.395400e+02 +15 1135 4.649100e+02 1.464800e+02 +16 1135 -7.274000e+02 2.977800e+02 +19 1135 2.101001e+01 2.061500e+02 +0 1136 -1.594460e+03 1.850300e+02 +4 1136 -2.449399e+02 2.884700e+02 +14 1136 -3.085700e+02 2.395400e+02 +15 1136 4.649100e+02 1.464800e+02 +16 1136 -7.274000e+02 2.977800e+02 +19 1136 2.101001e+01 2.061500e+02 +0 1137 -1.401420e+03 1.864099e+02 +4 1137 -1.453500e+02 2.903401e+02 +7 1137 -1.117230e+03 3.213800e+02 +14 1137 -2.139800e+02 2.385500e+02 +15 1137 5.825000e+02 1.481900e+02 +19 1137 2.082700e+02 2.141400e+02 +0 1138 1.523720e+03 1.872300e+02 +8 1138 7.626200e+02 2.259100e+02 +0 1139 -8.180900e+02 1.869199e+02 +4 1139 1.275500e+02 3.056599e+02 +7 1139 -7.438400e+02 3.361799e+02 +10 1139 -1.166730e+03 -3.782600e+02 +14 1139 5.769989e+00 2.355100e+02 +19 1139 7.183601e+02 2.325801e+02 +0 1140 -9.199600e+02 1.988800e+02 +4 1140 8.355005e+01 3.075400e+02 +0 1141 -1.227060e+03 2.003000e+02 +4 1141 -6.059998e+01 3.007900e+02 +7 1141 -9.854600e+02 3.342900e+02 +15 1141 6.804000e+02 1.593000e+02 +16 1141 -5.170300e+02 3.145900e+02 +19 1141 3.698300e+02 2.338000e+02 +0 1142 -9.949300e+02 2.059900e+02 +7 1142 -7.707100e+02 3.387800e+02 +0 1143 -8.239300e+02 2.122400e+02 +7 1143 -7.492900e+02 3.564199e+02 +19 1143 7.113101e+02 2.581699e+02 +0 1144 8.707000e+02 2.128900e+02 +4 1144 1.090030e+03 3.551100e+02 +5 1144 7.100100e+02 7.724600e+02 +6 1144 -8.832001e+01 8.215002e+01 +8 1144 -1.643800e+02 2.656700e+02 +0 1145 9.086499e+02 2.154700e+02 +8 1145 -1.003700e+02 2.673201e+02 +0 1146 7.456499e+02 2.193500e+02 +4 1146 1.005080e+03 3.493101e+02 +5 1146 5.985699e+02 7.539900e+02 +6 1146 -2.495000e+02 1.241700e+02 +0 1147 -1.124560e+03 2.199199e+02 +4 1147 -1.244995e+01 3.126799e+02 +7 1147 -9.179900e+02 3.512600e+02 +15 1147 7.345500e+02 1.731100e+02 +16 1147 -4.666100e+02 3.287400e+02 +19 1147 4.602200e+02 2.560500e+02 +0 1148 -1.500870e+03 2.201899e+02 +4 1148 -1.941000e+02 3.057800e+02 +0 1149 7.363999e+02 2.211799e+02 +4 1149 9.985500e+02 3.500500e+02 +5 1149 5.911700e+02 7.539000e+02 +0 1150 9.254099e+02 2.214900e+02 +4 1150 1.128190e+03 3.642100e+02 +5 1150 7.572400e+02 7.887300e+02 +6 1150 -2.283002e+01 8.203003e+01 +8 1150 -7.339001e+01 2.758000e+02 +0 1151 8.755200e+02 2.242300e+02 +4 1151 1.093640e+03 3.626200e+02 +5 1151 7.132700e+02 7.819399e+02 +8 1151 -1.553000e+02 2.836100e+02 +0 1152 8.212700e+02 2.259500e+02 +4 1152 1.056120e+03 3.590801e+02 +5 1152 6.648000e+02 7.732500e+02 +0 1153 -1.101670e+03 2.271300e+02 +4 1153 -2.619995e+00 3.175400e+02 +7 1153 -9.052700e+02 3.582400e+02 +14 1153 -9.003000e+01 2.552100e+02 +15 1153 7.452800e+02 1.784500e+02 +19 1153 4.790400e+02 2.643301e+02 +0 1154 8.122300e+02 2.281100e+02 +4 1154 1.049950e+03 3.596100e+02 +5 1154 6.561600e+02 7.731400e+02 +0 1155 8.060300e+02 2.278600e+02 +4 1155 1.045380e+03 3.579199e+02 +5 1155 6.503199e+02 7.709000e+02 +0 1156 -1.308390e+03 2.291200e+02 +4 1156 -1.006100e+02 3.136899e+02 +7 1156 -1.046700e+03 3.558900e+02 +14 1156 -1.731400e+02 2.575200e+02 +15 1156 6.343400e+02 1.744900e+02 +16 1156 -5.617500e+02 3.286400e+02 +19 1156 2.937300e+02 2.589900e+02 +0 1157 -1.494090e+03 2.294600e+02 +4 1157 -1.893800e+02 3.107100e+02 +15 1157 5.324500e+02 1.718200e+02 +16 1157 -6.604700e+02 3.238101e+02 +19 1157 1.256600e+02 2.526300e+02 +0 1158 -1.662710e+03 2.293000e+02 +4 1158 -2.808400e+02 3.106200e+02 +5 1158 -1.123140e+03 4.528700e+02 +19 1158 -4.604004e+01 2.456699e+02 +0 1159 8.908101e+02 2.345100e+02 +4 1159 1.104240e+03 3.700300e+02 +5 1159 7.258101e+02 7.933600e+02 +0 1160 1.010240e+03 2.351200e+02 +8 1160 7.640002e+01 2.887400e+02 +0 1161 1.010240e+03 2.351200e+02 +6 1161 7.027002e+01 7.303003e+01 +8 1161 7.640002e+01 2.887400e+02 +0 1162 6.632100e+02 2.346799e+02 +4 1162 9.533301e+02 3.530701e+02 +5 1162 5.295900e+02 7.520900e+02 +0 1163 7.900500e+02 2.361300e+02 +4 1163 1.034540e+03 3.623900e+02 +5 1163 6.351300e+02 7.749399e+02 +6 1163 -1.886500e+02 1.342500e+02 +0 1164 -1.266350e+03 2.360300e+02 +7 1164 -1.017600e+03 3.624299e+02 +14 1164 -1.559400e+02 2.604900e+02 +19 1164 3.312400e+02 2.673500e+02 +0 1165 -1.694070e+03 2.377500e+02 +4 1165 -2.984600e+02 3.145901e+02 +0 1166 -1.521720e+03 2.404800e+02 +4 1166 -2.051700e+02 3.163000e+02 +15 1166 5.137900e+02 1.782000e+02 +19 1166 9.619995e+01 2.627000e+02 +0 1167 8.636201e+02 2.457300e+02 +4 1167 1.085460e+03 3.737500e+02 +5 1167 6.999100e+02 7.962200e+02 +0 1168 8.622200e+02 2.528401e+02 +8 1168 -1.788300e+02 3.284700e+02 +0 1169 5.928701e+02 2.541200e+02 +4 1169 9.104800e+02 3.596500e+02 +5 1169 4.706700e+02 7.546799e+02 +0 1170 7.998000e+02 2.566899e+02 +4 1170 1.040960e+03 3.745601e+02 +5 1170 6.405300e+02 7.919900e+02 +0 1171 6.981799e+02 2.605801e+02 +5 1171 5.564500e+02 7.775500e+02 +0 1172 1.100900e+03 2.708500e+02 +4 1172 1.287450e+03 4.304700e+02 +8 1172 2.474200e+02 3.269600e+02 +0 1173 8.434299e+02 2.709399e+02 +4 1173 1.071750e+03 3.866500e+02 +5 1173 6.796801e+02 8.122400e+02 +6 1173 -1.181700e+02 1.649900e+02 +8 1173 -2.109800e+02 3.585000e+02 +0 1174 6.108601e+02 2.722300e+02 +4 1174 9.214700e+02 3.716100e+02 +0 1175 7.929199e+02 2.808000e+02 +4 1175 1.037170e+03 3.885801e+02 +5 1175 6.314500e+02 8.086799e+02 +0 1176 5.716001e+02 2.810801e+02 +7 1176 2.514800e+02 4.062200e+02 +0 1177 5.582000e+02 2.848900e+02 +4 1177 8.898301e+02 3.747100e+02 +8 1177 -7.136000e+02 4.043101e+02 +0 1178 5.582000e+02 2.848900e+02 +8 1178 -7.136000e+02 4.043101e+02 +0 1179 1.470460e+03 2.864800e+02 +8 1179 6.973800e+02 3.734100e+02 +0 1180 8.486299e+02 2.873600e+02 +6 1180 -1.107800e+02 1.842300e+02 +7 1180 3.907700e+02 4.304500e+02 +0 1181 8.486299e+02 2.873600e+02 +4 1181 1.075600e+03 3.980901e+02 +5 1181 6.827700e+02 8.264000e+02 +8 1181 -2.017600e+02 3.837500e+02 +0 1182 8.486299e+02 2.873600e+02 +8 1182 -2.017600e+02 3.837500e+02 +0 1183 4.813101e+02 2.893301e+02 +2 1183 -3.474000e+02 2.164100e+02 +7 1183 1.984500e+02 4.095901e+02 +11 1183 2.814600e+02 2.350400e+02 +0 1184 -8.466300e+02 2.895701e+02 +7 1184 -7.606200e+02 4.156200e+02 +10 1184 -1.176250e+03 -3.024200e+02 +16 1184 -3.423600e+02 3.795000e+02 +0 1185 5.622200e+02 2.929000e+02 +7 1185 2.468400e+02 4.138900e+02 +0 1186 1.566430e+03 2.960300e+02 +3 1186 1.024900e+03 4.314299e+02 +8 1186 8.209301e+02 3.919200e+02 +17 1186 -9.677300e+02 6.123401e+02 +0 1187 6.087700e+02 3.043101e+02 +8 1187 -6.208300e+02 4.304100e+02 +0 1188 6.087700e+02 3.043101e+02 +4 1188 9.208000e+02 3.880100e+02 +8 1188 -6.208300e+02 4.304100e+02 +0 1189 -8.632600e+02 3.172400e+02 +4 1189 1.055699e+02 3.734199e+02 +0 1190 5.326699e+02 3.179199e+02 +5 1190 4.176000e+02 7.926300e+02 +0 1191 -8.234200e+02 3.215500e+02 +7 1191 -7.516000e+02 4.424299e+02 +15 1191 8.831200e+02 2.471900e+02 +16 1191 -3.345400e+02 3.990300e+02 +19 1191 7.079500e+02 3.692100e+02 +0 1192 -8.234200e+02 3.215500e+02 +7 1192 -7.516000e+02 4.424299e+02 +10 1192 -1.167290e+03 -2.770400e+02 +16 1192 -3.345400e+02 3.990300e+02 +19 1192 7.079500e+02 3.692100e+02 +0 1193 -8.546800e+02 3.225100e+02 +4 1193 1.097000e+02 3.768201e+02 +15 1193 8.697800e+02 2.453600e+02 +19 1193 6.850701e+02 3.691799e+02 +0 1194 -8.670600e+02 3.288301e+02 +4 1194 1.037100e+02 3.794399e+02 +0 1195 -1.451580e+03 3.317600e+02 +4 1195 -1.730100e+02 3.641400e+02 +14 1195 -2.376600e+02 3.064500e+02 +15 1195 5.507800e+02 2.321300e+02 +19 1195 1.568900e+02 3.535200e+02 +0 1196 -1.465310e+03 3.327500e+02 +4 1196 -1.797300e+02 3.642700e+02 +15 1196 5.435500e+02 2.324500e+02 +19 1196 1.451200e+02 3.535400e+02 +0 1197 8.692200e+02 3.349299e+02 +4 1197 1.095470e+03 4.354199e+02 +5 1197 7.052600e+02 8.746000e+02 +7 1197 3.852800e+02 4.749399e+02 +8 1197 -1.518800e+02 4.516799e+02 +12 1197 -7.463100e+02 -3.489301e+02 +13 1197 -1.364140e+03 1.033520e+03 +0 1198 1.657580e+03 3.357000e+02 +7 1198 9.622200e+02 4.242000e+02 +10 1198 3.823401e+02 -3.114200e+02 +12 1198 -1.705500e+02 -4.286200e+02 +17 1198 -8.190700e+02 6.582000e+02 +18 1198 7.441003e+01 7.113000e+01 +20 1198 6.906006e+01 -1.339900e+02 +0 1199 1.701310e+03 3.390400e+02 +8 1199 1.004520e+03 4.545800e+02 +0 1200 7.675300e+02 3.507200e+02 +5 1200 6.145300e+02 8.666700e+02 +8 1200 -3.228100e+02 4.842800e+02 +0 1201 5.739500e+02 3.521100e+02 +4 1201 8.997100e+02 4.150100e+02 +5 1201 4.449200e+02 8.261799e+02 +8 1201 -6.833200e+02 5.130100e+02 +0 1202 6.249600e+02 3.571599e+02 +4 1202 9.313401e+02 4.217300e+02 +5 1202 4.862800e+02 8.390100e+02 +8 1202 -5.907500e+02 5.151400e+02 +0 1203 -1.657930e+03 3.583101e+02 +4 1203 -2.819200e+02 3.765801e+02 +5 1203 -1.141000e+03 5.445000e+02 +0 1204 -1.286720e+03 3.590100e+02 +5 1204 -8.826600e+02 5.915000e+02 +0 1205 1.585700e+03 3.596699e+02 +8 1205 8.463900e+02 4.888400e+02 +0 1206 -8.135600e+02 3.615100e+02 +4 1206 1.269700e+02 4.006200e+02 +18 1206 -1.287150e+03 1.369700e+02 +0 1207 -1.634180e+03 3.636200e+02 +4 1207 -2.704500e+02 3.794299e+02 +19 1207 -2.468005e+01 3.752100e+02 +0 1208 6.294500e+02 3.670000e+02 +5 1208 4.891400e+02 8.468400e+02 +0 1209 6.294500e+02 3.670000e+02 +5 1209 4.891400e+02 8.468400e+02 +0 1210 -1.589210e+03 3.665300e+02 +4 1210 -2.468600e+02 3.813700e+02 +15 1210 4.640200e+02 2.510800e+02 +16 1210 -7.337500e+02 4.011000e+02 +0 1211 -1.237900e+03 3.689299e+02 +4 1211 -6.933997e+01 3.871100e+02 +0 1212 -1.288930e+03 3.710701e+02 +4 1212 -9.381006e+01 3.873000e+02 +15 1212 6.429100e+02 2.582700e+02 +0 1213 5.671499e+02 3.744500e+02 +4 1213 8.962600e+02 4.270601e+02 +5 1213 4.380300e+02 8.421799e+02 +8 1213 -6.943300e+02 5.489600e+02 +0 1214 5.733899e+02 3.759299e+02 +8 1214 -6.831300e+02 5.495900e+02 +0 1215 -1.429460e+03 3.759399e+02 +4 1215 -1.637600e+02 3.874399e+02 +14 1215 -2.289900e+02 3.266000e+02 +15 1215 5.619700e+02 2.582300e+02 +19 1215 1.739399e+02 3.972400e+02 +0 1216 -1.565390e+03 3.776899e+02 +4 1216 -2.351500e+02 3.874299e+02 +5 1216 -1.079680e+03 5.694700e+02 +15 1216 4.781300e+02 2.574900e+02 +19 1216 4.131006e+01 3.918700e+02 +0 1217 -1.415700e+03 3.894700e+02 +4 1217 -1.577400e+02 3.949700e+02 +0 1218 5.892600e+02 4.012400e+02 +4 1218 9.096699e+02 4.437200e+02 +5 1218 4.528900e+02 8.661100e+02 +6 1218 -4.567400e+02 4.211799e+02 +8 1218 -6.541000e+02 5.902300e+02 +0 1219 6.320100e+02 4.330000e+02 +4 1219 9.372000e+02 4.667900e+02 +0 1220 4.806499e+02 4.386599e+02 +4 1220 8.459800e+02 4.597800e+02 +0 1221 4.631799e+02 4.395200e+02 +4 1221 8.349500e+02 4.598800e+02 +0 1222 4.570100e+02 4.450100e+02 +5 1222 3.464900e+02 8.790000e+02 +8 1222 -8.819200e+02 6.718199e+02 +10 1222 -2.930400e+02 -2.233600e+02 +0 1223 4.570100e+02 4.450100e+02 +4 1223 8.322000e+02 4.628401e+02 +0 1224 -9.147500e+02 4.538700e+02 +4 1224 8.121997e+01 4.438600e+02 +15 1224 8.397900e+02 3.223201e+02 +19 1224 6.331599e+02 4.991000e+02 +0 1225 6.260701e+02 4.642900e+02 +5 1225 4.781200e+02 9.238500e+02 +6 1225 -3.939100e+02 4.852100e+02 +8 1225 -5.794300e+02 6.837800e+02 +0 1226 -1.182910e+03 4.669000e+02 +4 1226 -4.383997e+01 4.395801e+02 +7 1226 -9.619600e+02 5.447400e+02 +15 1226 7.010800e+02 3.178700e+02 +0 1227 -1.232310e+03 4.706599e+02 +7 1227 -9.975500e+02 5.472200e+02 +0 1228 5.152900e+02 4.730901e+02 +4 1228 8.670601e+02 4.812300e+02 +5 1228 3.880900e+02 9.087800e+02 +0 1229 1.637380e+03 4.893700e+02 +2 1229 6.154000e+02 4.467400e+02 +8 1229 9.515800e+02 6.476600e+02 +12 1229 -2.287100e+02 -2.647000e+02 +0 1230 -1.189820e+03 4.920801e+02 +7 1230 -9.710200e+02 5.653600e+02 +10 1230 -1.357300e+03 -1.538300e+02 +15 1230 6.954500e+02 3.330701e+02 +20 1230 -1.244040e+03 -1.954999e+01 +0 1231 -1.223890e+03 4.949099e+02 +4 1231 -6.516003e+01 4.532000e+02 +16 1231 -5.281400e+02 4.816400e+02 +0 1232 -1.663680e+03 4.963800e+02 +4 1232 -2.890900e+02 4.475701e+02 +0 1233 -9.089200e+02 5.016300e+02 +7 1233 -7.973400e+02 5.802700e+02 +19 1233 6.347600e+02 5.479800e+02 +0 1234 -1.362800e+03 5.024199e+02 +4 1234 -1.324900e+02 4.537400e+02 +15 1234 5.990900e+02 3.332700e+02 +0 1235 -8.179700e+02 5.076200e+02 +4 1235 1.231899e+02 4.793600e+02 +14 1235 6.450012e+00 3.825700e+02 +15 1235 8.829100e+02 3.630000e+02 +16 1235 -3.383200e+02 5.068900e+02 +18 1235 -1.288170e+03 2.359600e+02 +19 1235 7.058899e+02 5.589000e+02 +20 1235 -1.105160e+03 2.849976e+00 +0 1236 -1.578420e+03 5.108600e+02 +4 1236 -2.450500e+02 4.560801e+02 +0 1237 5.329399e+02 5.180500e+02 +5 1237 4.032900e+02 9.546000e+02 +0 1238 -1.387020e+03 5.202600e+02 +4 1238 -1.447900e+02 4.626799e+02 +10 1238 -1.503520e+03 -1.261899e+02 +14 1238 -2.099700e+02 3.936300e+02 +15 1238 5.843800e+02 3.430400e+02 +16 1238 -6.181900e+02 4.925800e+02 +19 1238 2.108400e+02 5.396200e+02 +0 1239 -1.194190e+03 5.459900e+02 +4 1239 -5.207996e+01 4.809700e+02 +7 1239 -9.763400e+02 6.076600e+02 +10 1239 -1.358860e+03 -1.129500e+02 +15 1239 6.916300e+02 3.646000e+02 +16 1239 -5.141500e+02 5.118500e+02 +19 1239 3.857600e+02 5.756400e+02 +0 1240 -1.173600e+03 5.696500e+02 +4 1240 -4.185999e+01 4.943500e+02 +16 1240 -5.038600e+02 5.260000e+02 +0 1241 -1.173600e+03 5.696500e+02 +4 1241 -4.185999e+01 4.943500e+02 +5 1241 -8.388700e+02 7.571100e+02 +16 1241 -5.038600e+02 5.260000e+02 +0 1242 -1.232790e+03 5.750300e+02 +4 1242 -7.094995e+01 4.950800e+02 +0 1243 -1.362980e+03 5.838900e+02 +4 1243 -1.343600e+02 4.960400e+02 +0 1244 -1.189420e+03 5.929199e+02 +4 1244 -4.996997e+01 5.058800e+02 +7 1244 -9.733500e+02 6.459200e+02 +14 1244 -1.232900e+02 4.256100e+02 +15 1244 6.941600e+02 3.928700e+02 +19 1244 3.896100e+02 6.229900e+02 +0 1245 -1.368110e+03 6.050601e+02 +4 1245 -1.368199e+02 5.070900e+02 +5 1245 -9.760000e+02 7.568800e+02 +15 1245 5.950601e+02 3.930000e+02 +19 1245 2.260900e+02 6.235800e+02 +0 1246 -8.006300e+02 6.249700e+02 +4 1246 1.291000e+02 5.450400e+02 +0 1247 -1.604470e+03 6.725900e+02 +4 1247 -2.638400e+02 5.400200e+02 +14 1247 -3.194200e+02 4.674299e+02 +15 1247 4.462800e+02 4.272900e+02 +0 1248 -1.022680e+03 6.845500e+02 +4 1248 2.663000e+01 5.624800e+02 +14 1248 -5.842999e+01 4.655000e+02 +0 1249 -9.126900e+02 6.883800e+02 +4 1249 7.813000e+01 5.705800e+02 +7 1249 -8.010500e+02 7.284700e+02 +10 1249 -1.189230e+03 -8.229980e+00 +15 1249 8.372500e+02 4.663900e+02 +19 1249 6.273899e+02 7.364399e+02 +20 1249 -1.123430e+03 9.884009e+01 +0 1250 -1.473970e+03 6.949200e+02 +4 1250 -1.962300e+02 5.534100e+02 +5 1250 -1.067810e+03 8.095200e+02 +0 1251 -1.420920e+03 6.966500e+02 +4 1251 -1.683199e+02 5.548900e+02 +15 1251 5.580500e+02 4.457200e+02 +0 1252 -1.484270e+03 7.035100e+02 +4 1252 -2.010000e+02 5.580701e+02 +5 1252 -1.076190e+03 8.140601e+02 +15 1252 5.203800e+02 4.486100e+02 +19 1252 1.075100e+02 7.112100e+02 +0 1253 -1.526020e+03 7.027500e+02 +4 1253 -2.229500e+02 5.567600e+02 +15 1253 4.942100e+02 4.468800e+02 +0 1254 -1.581640e+03 7.111799e+02 +4 1254 -2.519900e+02 5.605000e+02 +5 1254 -1.146630e+03 8.070300e+02 +15 1254 4.605900e+02 4.502800e+02 +16 1254 -7.456000e+02 6.030400e+02 +0 1255 -1.713840e+03 7.174299e+02 +4 1255 -3.202000e+02 5.614800e+02 +0 1256 -1.030140e+03 7.269900e+02 +4 1256 2.165002e+01 5.847000e+02 +7 1256 -8.765400e+02 7.562400e+02 +10 1256 -1.255880e+03 2.078003e+01 +15 1256 7.740400e+02 4.821000e+02 +19 1256 5.225200e+02 7.664600e+02 +0 1257 -1.684200e+03 7.387700e+02 +4 1257 -3.039500e+02 5.727100e+02 +14 1257 -3.575500e+02 4.998101e+02 +15 1257 3.995699e+02 4.628101e+02 +19 1257 -8.381995e+01 7.286600e+02 +0 1258 -1.598070e+03 7.543101e+02 +4 1258 -2.627100e+02 5.835000e+02 +15 1258 4.479900e+02 4.755000e+02 +16 1258 -7.618900e+02 6.292500e+02 +19 1258 -6.579956e+00 7.502000e+02 +0 1259 -1.506830e+03 7.617600e+02 +4 1259 -2.150800e+02 5.883400e+02 +5 1259 -1.102130e+03 8.539100e+02 +10 1259 -1.607720e+03 7.114001e+01 +14 1259 -2.713500e+02 5.088900e+02 +15 1259 5.037900e+02 4.820800e+02 +0 1260 -1.367810e+03 8.327800e+02 +4 1260 -1.448101e+02 6.278600e+02 +5 1260 -1.015640e+03 9.242000e+02 +14 1260 -2.049500e+02 5.405400e+02 +15 1260 5.850500e+02 5.276300e+02 +19 1260 2.120601e+02 8.460000e+02 +0 1261 -1.506250e+03 8.580100e+02 +4 1261 -2.164800e+02 6.390300e+02 +5 1261 -1.117380e+03 9.251700e+02 +15 1261 5.023199e+02 5.381300e+02 +19 1261 7.940002e+01 8.581400e+02 +0 1262 -1.480760e+03 8.589800e+02 +4 1262 -2.037300e+02 6.399600e+02 +5 1262 -1.100360e+03 9.287600e+02 +20 1262 -1.421570e+03 2.091899e+02 +0 1263 -1.075320e+03 8.717900e+02 +4 1263 -1.538000e+01 6.712500e+02 +0 1264 -1.424990e+03 8.758800e+02 +4 1264 -1.752400e+02 6.493000e+02 +5 1264 -1.063090e+03 9.483300e+02 +15 1264 5.509100e+02 5.509100e+02 +16 1264 -6.586400e+02 7.005300e+02 +0 1265 -1.291050e+03 8.986699e+02 +4 1265 -1.250300e+02 6.765701e+02 +14 1265 -1.950200e+02 5.726200e+02 +15 1265 5.996100e+02 5.802400e+02 +16 1265 -6.114600e+02 7.269301e+02 +19 1265 2.443199e+02 9.158800e+02 +0 1266 7.695801e+02 -8.103003e+01 +4 1266 1.015550e+03 1.743301e+02 +0 1267 8.177200e+02 -4.851001e+01 +5 1267 6.882900e+02 5.605200e+02 +0 1268 7.859299e+02 -3.505005e+01 +4 1268 1.028080e+03 2.033000e+02 +0 1269 8.403501e+02 2.398999e+01 +4 1269 1.065330e+03 2.397400e+02 +0 1270 8.483601e+02 3.968005e+01 +5 1270 7.074600e+02 6.329100e+02 +8 1270 -2.028300e+02 -3.950012e+00 +0 1271 7.811299e+02 4.648999e+01 +5 1271 6.461899e+02 6.273000e+02 +0 1272 8.768101e+02 5.067004e+01 +4 1272 1.092010e+03 2.574299e+02 +8 1272 -1.533800e+02 1.259998e+01 +0 1273 8.486001e+02 5.397998e+01 +8 1273 -2.019200e+02 1.845001e+01 +0 1274 8.769900e+02 6.123999e+01 +8 1274 -1.530200e+02 2.820001e+01 +0 1275 -1.184390e+03 6.497998e+01 +7 1275 -9.536300e+02 2.296200e+02 +15 1275 7.043700e+02 8.046997e+01 +0 1276 -1.319170e+03 6.853003e+01 +7 1276 -1.047050e+03 2.296799e+02 +0 1277 7.667800e+02 7.845996e+01 +6 1277 -2.292200e+02 -6.820001e+01 +0 1278 5.785801e+02 8.152002e+01 +4 1278 8.993999e+02 2.616400e+02 +5 1278 4.764900e+02 6.233000e+02 +0 1279 5.123799e+02 8.251001e+01 +5 1279 4.255900e+02 6.160400e+02 +0 1280 7.406899e+02 8.527002e+01 +4 1280 1.000940e+03 2.709800e+02 +0 1281 -1.068340e+03 8.541003e+01 +4 1281 1.617004e+01 2.444000e+02 +7 1281 -8.758800e+02 2.481899e+02 +10 1281 -1.288690e+03 -4.617600e+02 +15 1281 7.669100e+02 9.444000e+01 +20 1281 -1.189750e+03 -2.526700e+02 +0 1282 7.657200e+02 9.334998e+01 +5 1282 6.281700e+02 6.598800e+02 +0 1283 1.004280e+03 9.617004e+01 +8 1283 6.306006e+01 7.773999e+01 +0 1284 1.030100e+03 9.831995e+01 +8 1284 1.070900e+02 7.939001e+01 +0 1285 1.020260e+03 9.881006e+01 +4 1285 1.199920e+03 2.971500e+02 +0 1286 9.672900e+02 1.056899e+02 +4 1286 1.158160e+03 2.968900e+02 +0 1287 7.804099e+02 1.052800e+02 +5 1287 6.387800e+02 6.718500e+02 +0 1288 7.570801e+02 1.062400e+02 +2 1288 -1.739400e+02 1.371002e+01 +7 1288 3.460100e+02 2.898700e+02 +9 1288 -2.220699e+02 1.601599e+02 +11 1288 4.178900e+02 9.946002e+01 +0 1289 1.495940e+03 1.100900e+02 +2 1289 6.226500e+02 7.440002e+00 +3 1289 7.686500e+02 7.159003e+01 +12 1289 -2.821400e+02 -5.520500e+02 +17 1289 -1.173050e+03 3.419900e+02 +0 1290 9.531299e+02 1.121700e+02 +8 1290 -2.328998e+01 1.049600e+02 +0 1291 1.063520e+03 1.126000e+02 +4 1291 1.237960e+03 3.112700e+02 +0 1292 9.435000e+02 1.146700e+02 +8 1292 -4.004999e+01 1.093400e+02 +0 1293 8.711599e+02 1.214100e+02 +5 1293 7.192500e+02 7.002900e+02 +8 1293 -1.638700e+02 1.241300e+02 +0 1294 1.027280e+03 1.241200e+02 +8 1294 1.038199e+02 1.188700e+02 +0 1295 1.023730e+03 1.271899e+02 +5 1295 8.642200e+02 7.346400e+02 +8 1295 9.690002e+01 1.245100e+02 +0 1296 8.548401e+02 1.279000e+02 +5 1296 7.036700e+02 7.029200e+02 +6 1296 -1.129500e+02 -2.094000e+01 +8 1296 -1.923100e+02 1.352500e+02 +0 1297 1.011480e+03 1.296899e+02 +8 1297 7.775000e+01 1.279700e+02 +0 1298 9.239299e+02 1.314199e+02 +4 1298 1.126050e+03 3.090100e+02 +0 1299 6.160801e+02 1.403401e+02 +4 1299 9.234199e+02 2.965100e+02 +5 1299 5.004301e+02 6.727600e+02 +0 1300 9.553101e+02 1.424600e+02 +8 1300 -1.920001e+01 1.511300e+02 +0 1301 9.167500e+02 1.464000e+02 +5 1301 7.572700e+02 7.279800e+02 +8 1301 -8.732001e+01 1.599800e+02 +0 1302 1.007300e+03 1.507500e+02 +4 1302 1.190510e+03 3.289299e+02 +5 1302 8.451699e+02 7.500100e+02 +8 1302 6.938000e+01 1.603800e+02 +0 1303 8.745400e+02 1.543800e+02 +4 1303 1.091680e+03 3.197700e+02 +5 1303 7.188800e+02 7.267200e+02 +6 1303 -8.769000e+01 7.369995e+00 +8 1303 -1.583800e+02 1.743400e+02 +0 1304 8.949299e+02 1.551899e+02 +5 1304 7.365800e+02 7.310701e+02 +8 1304 -1.242700e+02 1.754600e+02 +0 1305 9.682300e+02 1.563201e+02 +8 1305 3.030029e+00 1.714700e+02 +0 1306 8.956599e+02 1.596899e+02 +5 1306 7.374700e+02 7.346000e+02 +8 1306 -1.213600e+02 1.814800e+02 +0 1307 8.863000e+02 1.598201e+02 +5 1307 7.289399e+02 7.333900e+02 +6 1307 -7.277002e+01 1.208002e+01 +8 1307 -1.380600e+02 1.825500e+02 +0 1308 9.710200e+02 1.626899e+02 +5 1308 8.080901e+02 7.509900e+02 +8 1308 7.170044e+00 1.811300e+02 +0 1309 8.913501e+02 1.660500e+02 +8 1309 -1.294100e+02 1.922800e+02 +0 1310 8.913501e+02 1.660500e+02 +5 1310 7.328000e+02 7.392600e+02 +8 1310 -1.294100e+02 1.922800e+02 +0 1311 9.348401e+02 1.667300e+02 +5 1311 7.730000e+02 7.474500e+02 +8 1311 -5.477002e+01 1.894300e+02 +0 1312 7.058000e+02 1.670000e+02 +4 1312 9.793501e+02 3.167400e+02 +0 1313 9.752900e+02 1.736100e+02 +8 1313 1.456006e+01 1.973800e+02 +0 1314 8.909199e+02 1.763101e+02 +4 1314 1.103550e+03 3.343700e+02 +5 1314 7.314700e+02 7.468900e+02 +6 1314 -6.622998e+01 3.132001e+01 +8 1314 -1.301900e+02 2.074500e+02 +0 1315 7.055200e+02 1.784099e+02 +4 1315 9.793000e+02 3.234299e+02 +0 1316 1.169770e+03 1.797700e+02 +2 1316 -8.712000e+01 1.554300e+02 +3 1316 -2.852600e+02 1.069400e+02 +8 1316 3.407500e+02 1.914900e+02 +9 1316 -1.017800e+02 3.168301e+02 +11 1316 5.128600e+02 2.490300e+02 +13 1316 -9.596000e+02 6.282800e+02 +0 1317 1.592190e+03 1.834900e+02 +2 1317 7.785300e+02 7.016998e+01 +6 1317 8.778700e+02 4.400000e+01 +8 1317 8.552900e+02 2.211500e+02 +12 1317 -2.092400e+02 -5.192200e+02 +17 1317 -9.192100e+02 4.316300e+02 +0 1318 9.833501e+02 1.846799e+02 +4 1318 1.171870e+03 3.480701e+02 +0 1319 1.546870e+03 1.861899e+02 +8 1319 7.935100e+02 2.249600e+02 +0 1320 1.577300e+03 1.904399e+02 +2 1320 7.621801e+02 7.846002e+01 +6 1320 8.550500e+02 5.252002e+01 +7 1320 9.106001e+02 3.319399e+02 +8 1320 8.350300e+02 2.316000e+02 +12 1320 -2.181899e+02 -5.138400e+02 +16 1320 9.709399e+02 3.536000e+02 +17 1320 -9.463800e+02 4.446400e+02 +0 1321 1.593170e+03 1.953101e+02 +8 1321 8.569399e+02 2.390900e+02 +0 1322 9.163301e+02 2.030601e+02 +5 1322 7.520500e+02 7.729100e+02 +8 1322 -8.710999e+01 2.478700e+02 +0 1323 1.463310e+03 2.052600e+02 +8 1323 6.878300e+02 2.496200e+02 +0 1324 1.463310e+03 2.052600e+02 +8 1324 6.878300e+02 2.496200e+02 +0 1325 9.855601e+02 2.089399e+02 +8 1325 3.307996e+01 2.507600e+02 +0 1326 8.787400e+02 2.109500e+02 +4 1326 1.095750e+03 3.547200e+02 +5 1326 7.177300e+02 7.722600e+02 +6 1326 -7.919000e+01 7.776001e+01 +8 1326 -1.499100e+02 2.620100e+02 +0 1327 8.787400e+02 2.109500e+02 +4 1327 1.095750e+03 3.547200e+02 +5 1327 7.177300e+02 7.722600e+02 +6 1327 -7.919000e+01 7.776001e+01 +8 1327 -1.499100e+02 2.620100e+02 +0 1328 9.513601e+02 2.124600e+02 +4 1328 1.148680e+03 3.627000e+02 +5 1328 7.846599e+02 7.884000e+02 +6 1328 5.689941e+00 6.140997e+01 +8 1328 -2.558002e+01 2.591500e+02 +0 1329 9.513601e+02 2.124600e+02 +6 1329 5.689941e+00 6.140997e+01 +8 1329 -2.558002e+01 2.591500e+02 +0 1330 -1.018290e+03 2.172900e+02 +7 1330 -8.528200e+02 3.524800e+02 +10 1330 -1.260540e+03 -3.613500e+02 +15 1330 7.895400e+02 1.750500e+02 +0 1331 5.816499e+02 2.197000e+02 +4 1331 9.033899e+02 3.400500e+02 +0 1332 9.105400e+02 2.212500e+02 +6 1332 -3.935999e+01 8.508002e+01 +8 1332 -9.698999e+01 2.761000e+02 +0 1333 9.147100e+02 2.244299e+02 +6 1333 -3.465002e+01 8.867999e+01 +8 1333 -9.232001e+01 2.811799e+02 +0 1334 9.863301e+02 2.285500e+02 +8 1334 3.569995e+01 2.809600e+02 +0 1335 -1.245230e+03 2.309900e+02 +7 1335 -1.000620e+03 3.581500e+02 +15 1335 6.690800e+02 1.776700e+02 +0 1336 8.576001e+02 2.315601e+02 +5 1336 6.959200e+02 7.843500e+02 +0 1337 8.559900e+02 2.366899e+02 +4 1337 1.080210e+03 3.683301e+02 +5 1337 6.940500e+02 7.882300e+02 +8 1337 -1.893600e+02 3.039399e+02 +0 1338 6.387000e+02 2.388401e+02 +5 1338 5.087600e+02 7.510300e+02 +0 1339 8.525200e+02 2.405601e+02 +4 1339 1.077750e+03 3.705801e+02 +5 1339 6.909200e+02 7.904700e+02 +8 1339 -1.956600e+02 3.099000e+02 +0 1340 8.434399e+02 2.490701e+02 +4 1340 1.071280e+03 3.748900e+02 +5 1340 6.813300e+02 7.954600e+02 +8 1340 -2.115700e+02 3.250300e+02 +0 1341 8.434399e+02 2.490701e+02 +8 1341 -2.115700e+02 3.250300e+02 +0 1342 6.071101e+02 2.512000e+02 +4 1342 9.199800e+02 3.589299e+02 +5 1342 4.834500e+02 7.551600e+02 +0 1343 7.371899e+02 2.521500e+02 +5 1343 5.887400e+02 7.776400e+02 +0 1344 7.944099e+02 2.540100e+02 +4 1344 1.037480e+03 3.729600e+02 +0 1345 7.850500e+02 2.558101e+02 +4 1345 1.031380e+03 3.725000e+02 +5 1345 6.292400e+02 7.882800e+02 +0 1346 7.339399e+02 2.580000e+02 +4 1346 9.981499e+02 3.712100e+02 +5 1346 5.854100e+02 7.816300e+02 +0 1347 8.612100e+02 2.586699e+02 +6 1347 -9.734003e+01 1.433800e+02 +8 1347 -1.801600e+02 3.374299e+02 +0 1348 7.431799e+02 2.629099e+02 +5 1348 5.931200e+02 7.873900e+02 +0 1349 7.431799e+02 2.629099e+02 +5 1349 5.931200e+02 7.873900e+02 +0 1350 7.170400e+02 2.665601e+02 +4 1350 9.877700e+02 3.756300e+02 +5 1350 5.709600e+02 7.862400e+02 +0 1351 6.449299e+02 2.686300e+02 +4 1351 9.426699e+02 3.720701e+02 +0 1352 7.502500e+02 2.735300e+02 +5 1352 5.973000e+02 7.966600e+02 +0 1353 7.502500e+02 2.735300e+02 +5 1353 5.973000e+02 7.966600e+02 +0 1354 5.922100e+02 2.757000e+02 +5 1354 4.680601e+02 7.710000e+02 +8 1354 -6.521300e+02 3.865100e+02 +0 1355 7.968201e+02 2.764900e+02 +5 1355 6.358101e+02 8.064600e+02 +0 1356 7.968201e+02 2.764900e+02 +5 1356 6.358101e+02 8.064600e+02 +0 1357 -1.061890e+03 2.815100e+02 +7 1357 -8.790100e+02 4.012000e+02 +19 1357 5.137800e+02 3.208301e+02 +0 1358 8.499199e+02 2.831100e+02 +5 1358 6.839000e+02 8.231000e+02 +8 1358 -1.994500e+02 3.765601e+02 +0 1359 8.546699e+02 2.838201e+02 +5 1359 6.877200e+02 8.249500e+02 +8 1359 -1.921100e+02 3.783000e+02 +0 1360 -1.400410e+03 2.863000e+02 +4 1360 -1.465900e+02 3.413500e+02 +15 1360 5.812700e+02 2.060400e+02 +0 1361 1.554770e+03 2.918101e+02 +3 1361 1.001780e+03 4.239900e+02 +8 1361 8.035699e+02 3.857800e+02 +0 1362 8.498501e+02 2.930801e+02 +8 1362 -2.014100e+02 3.935100e+02 +0 1363 -9.199100e+02 2.998201e+02 +7 1363 -7.968600e+02 4.202600e+02 +19 1363 6.342400e+02 3.436300e+02 +0 1364 1.617440e+03 3.009199e+02 +6 1364 9.112300e+02 1.984600e+02 +8 1364 8.894600e+02 3.989800e+02 +0 1365 8.588000e+02 3.029600e+02 +4 1365 1.082400e+03 4.079099e+02 +0 1366 5.481499e+02 3.087000e+02 +5 1366 4.295601e+02 7.885400e+02 +0 1367 5.053899e+02 3.332200e+02 +4 1367 8.590601e+02 4.015701e+02 +8 1367 -8.025000e+02 4.856799e+02 +0 1368 4.760300e+02 3.563600e+02 +3 1368 -1.068880e+03 7.380500e+02 +7 1368 1.951400e+02 4.576200e+02 +9 1368 -3.767600e+02 3.615000e+02 +11 1368 2.769301e+02 2.931900e+02 +0 1369 7.626001e+02 3.604399e+02 +5 1369 6.099200e+02 8.744800e+02 +8 1369 -3.302200e+02 4.995800e+02 +0 1370 -1.571100e+03 3.727300e+02 +4 1370 -2.378199e+02 3.846699e+02 +16 1370 -7.229600e+02 4.055400e+02 +19 1370 3.514001e+01 3.867100e+02 +0 1371 -1.613960e+03 3.777700e+02 +4 1371 -2.609301e+02 3.874299e+02 +15 1371 4.477500e+02 2.575400e+02 +19 1371 -6.150024e+00 3.895500e+02 +0 1372 6.759199e+02 3.828401e+02 +4 1372 9.663401e+02 4.484299e+02 +5 1372 5.333400e+02 8.754100e+02 +8 1372 -4.793900e+02 5.442900e+02 +0 1373 5.031299e+02 3.830100e+02 +5 1373 3.882400e+02 8.382700e+02 +7 1373 2.112900e+02 4.774500e+02 +8 1373 -8.046600e+02 5.670400e+02 +9 1373 -3.594600e+02 3.879600e+02 +10 1373 -2.692600e+02 -2.640601e+02 +11 1373 2.939900e+02 3.174500e+02 +18 1373 -4.955300e+02 1.248101e+02 +20 1373 -4.199000e+02 -9.071997e+01 +0 1374 6.276001e+02 3.842900e+02 +5 1374 4.855100e+02 8.593900e+02 +8 1374 -5.874100e+02 5.585701e+02 +0 1375 6.714900e+02 3.880901e+02 +4 1375 9.635200e+02 4.516200e+02 +5 1375 5.296500e+02 8.790699e+02 +0 1376 6.060300e+02 3.900300e+02 +8 1376 -6.253900e+02 5.700500e+02 +0 1377 5.929299e+02 3.932800e+02 +4 1377 9.117200e+02 4.395100e+02 +5 1377 4.565400e+02 8.601600e+02 +8 1377 -6.473500e+02 5.762900e+02 +0 1378 5.787600e+02 3.967800e+02 +8 1378 -6.738900e+02 5.834200e+02 +0 1379 5.606001e+02 3.971200e+02 +8 1379 -7.052200e+02 5.857900e+02 +0 1380 5.839099e+02 3.992700e+02 +5 1380 4.486500e+02 8.631400e+02 +0 1381 5.556799e+02 4.005400e+02 +5 1381 4.256801e+02 8.594399e+02 +0 1382 5.774199e+02 4.014299e+02 +5 1382 4.437400e+02 8.635601e+02 +8 1382 -6.760700e+02 5.910200e+02 +0 1383 5.454299e+02 4.125901e+02 +8 1383 -7.298600e+02 6.116300e+02 +0 1384 6.199299e+02 4.208500e+02 +5 1384 4.761200e+02 8.868101e+02 +0 1385 5.577800e+02 4.269500e+02 +4 1385 8.913401e+02 4.566400e+02 +8 1385 -7.084000e+02 6.331000e+02 +0 1386 -8.146100e+02 4.338301e+02 +4 1386 1.255601e+02 4.392900e+02 +15 1386 8.859000e+02 3.169500e+02 +0 1387 6.085200e+02 4.615200e+02 +5 1387 4.627100e+02 9.160601e+02 +0 1388 5.966201e+02 4.650400e+02 +5 1388 4.525800e+02 9.162800e+02 +0 1389 5.366399e+02 4.790300e+02 +8 1389 -7.434500e+02 7.198600e+02 +0 1390 1.597920e+03 4.832900e+02 +2 1390 5.800300e+02 4.440300e+02 +3 1390 6.198900e+02 6.297400e+02 +6 1390 7.497900e+02 3.313700e+02 +7 1390 8.906899e+02 5.716300e+02 +8 1390 9.009100e+02 6.413600e+02 +12 1390 -2.520000e+02 -2.670400e+02 +16 1390 9.858900e+02 5.449700e+02 +17 1390 -1.282860e+03 1.020830e+03 +0 1391 4.834299e+02 4.892300e+02 +4 1391 8.481799e+02 4.912300e+02 +0 1392 -9.133600e+02 5.080300e+02 +4 1392 8.068994e+01 4.732000e+02 +0 1393 -1.182610e+03 5.685400e+02 +7 1393 -9.691700e+02 6.265100e+02 +19 1393 3.962900e+02 5.993700e+02 +0 1394 -1.634110e+03 5.765200e+02 +4 1394 -2.760000e+02 4.890300e+02 +0 1395 -6.838600e+02 5.823800e+02 +4 1395 1.737500e+02 5.360900e+02 +0 1396 -8.056200e+02 5.917700e+02 +4 1396 1.268600e+02 5.271899e+02 +19 1396 7.118501e+02 6.450200e+02 +0 1397 -7.860500e+02 6.200701e+02 +4 1397 1.358400e+02 5.441300e+02 +0 1398 -1.412430e+03 6.562300e+02 +4 1398 -1.631500e+02 5.335200e+02 +0 1399 -9.074200e+02 6.579299e+02 +4 1399 8.078003e+01 5.548201e+02 +10 1399 -1.191640e+03 -2.904004e+01 +15 1399 8.383900e+02 4.487600e+02 +0 1400 -1.187750e+03 7.063700e+02 +4 1400 -5.277002e+01 5.662400e+02 +5 1400 -8.704500e+02 8.550000e+02 +7 1400 -9.787200e+02 7.377000e+02 +15 1400 6.908500e+02 4.607200e+02 +0 1401 -1.048900e+03 7.222800e+02 +4 1401 1.393005e+01 5.808400e+02 +7 1401 -8.861800e+02 7.514000e+02 +10 1401 -1.264970e+03 1.723999e+01 +16 1401 -4.492600e+02 6.187700e+02 +18 1401 -1.375870e+03 3.666799e+02 +19 1401 5.084900e+02 7.609800e+02 +20 1401 -1.177500e+03 1.146500e+02 +0 1402 -1.128960e+03 7.433600e+02 +5 1402 -8.371200e+02 8.925900e+02 +7 1402 -9.431400e+02 7.693500e+02 +16 1402 -4.909400e+02 6.298000e+02 +19 1402 4.331600e+02 7.763900e+02 +0 1403 -1.204570e+03 7.521000e+02 +4 1403 -6.144995e+01 5.903101e+02 +5 1403 -8.889200e+02 8.873199e+02 +7 1403 -9.931700e+02 7.750500e+02 +10 1403 -1.362390e+03 4.356006e+01 +0 1404 -1.409880e+03 7.652700e+02 +4 1404 -1.643600e+02 5.908000e+02 +5 1404 -1.033570e+03 8.684100e+02 +15 1404 5.630601e+02 4.860100e+02 +19 1404 1.750200e+02 7.759000e+02 +0 1405 -1.064240e+03 8.595100e+02 +4 1405 -9.410034e+00 6.649399e+02 +16 1405 -4.789800e+02 7.075500e+02 +0 1406 -1.431840e+03 9.605601e+02 +4 1406 -1.878700e+02 6.988101e+02 +15 1406 5.325601e+02 6.041799e+02 +0 1407 7.781001e+02 -4.035999e+01 +4 1407 1.022360e+03 1.992800e+02 +0 1408 -1.387930e+03 7.670044e+00 +7 1408 -1.097050e+03 1.813201e+02 +19 1408 2.292900e+02 4.122998e+01 +0 1409 8.601499e+02 1.391003e+01 +8 1409 -1.853200e+02 -4.351001e+01 +0 1410 6.347500e+02 6.933997e+01 +4 1410 9.340400e+02 2.570100e+02 +0 1411 1.102850e+03 7.165002e+01 +8 1411 2.277900e+02 3.629999e+01 +0 1412 8.805200e+02 7.389001e+01 +8 1412 -1.468500e+02 4.845001e+01 +0 1413 9.086799e+02 8.404004e+01 +8 1413 -1.018300e+02 6.414001e+01 +0 1414 1.096850e+03 9.042004e+01 +4 1414 1.263620e+03 2.990300e+02 +0 1415 9.512200e+02 1.000300e+02 +8 1415 -2.614001e+01 8.484003e+01 +0 1416 9.952800e+02 1.056100e+02 +8 1416 4.892004e+01 9.215002e+01 +0 1417 8.511101e+02 1.249600e+02 +8 1417 -1.984600e+02 1.291300e+02 +0 1418 9.642900e+02 1.425400e+02 +5 1418 8.039199e+02 7.341700e+02 +0 1419 9.189500e+02 1.501100e+02 +5 1419 7.588401e+02 7.315800e+02 +8 1419 -8.270001e+01 1.651500e+02 +0 1420 9.229900e+02 1.515200e+02 +4 1420 1.125670e+03 3.210300e+02 +5 1420 7.623401e+02 7.327700e+02 +0 1421 9.111899e+02 1.519600e+02 +8 1421 -9.790002e+01 1.692500e+02 +0 1422 8.703999e+02 1.529000e+02 +4 1422 1.088800e+03 3.180400e+02 +0 1423 8.757300e+02 1.582500e+02 +5 1423 7.191801e+02 7.302300e+02 +0 1424 9.998999e+02 1.633700e+02 +4 1424 1.185230e+03 3.363401e+02 +0 1425 8.090901e+02 1.686300e+02 +4 1425 1.046700e+03 3.233600e+02 +5 1425 6.593101e+02 7.260500e+02 +0 1426 8.180701e+02 1.706699e+02 +5 1426 6.666100e+02 7.296400e+02 +0 1427 5.890901e+02 1.725400e+02 +5 1427 4.756000e+02 6.926300e+02 +0 1428 9.190000e+02 1.733101e+02 +8 1428 -8.254999e+01 2.010800e+02 +0 1429 9.367600e+02 1.741599e+02 +8 1429 -5.169000e+01 2.012500e+02 +0 1430 7.082300e+02 1.856500e+02 +5 1430 5.722700e+02 7.225000e+02 +0 1431 1.614550e+03 1.896599e+02 +8 1431 8.861200e+02 2.306500e+02 +0 1432 6.905300e+02 1.943700e+02 +5 1432 5.571400e+02 7.262100e+02 +0 1433 6.933301e+02 1.972700e+02 +5 1433 5.584200e+02 7.293201e+02 +0 1434 1.466410e+03 2.083201e+02 +8 1434 6.920300e+02 2.546600e+02 +0 1435 9.435701e+02 2.152000e+02 +5 1435 7.775100e+02 7.889500e+02 +8 1435 -3.809003e+01 2.634200e+02 +0 1436 8.788301e+02 2.151300e+02 +5 1436 7.174301e+02 7.759299e+02 +6 1436 -7.801001e+01 8.215997e+01 +8 1436 -1.494900e+02 2.688700e+02 +0 1437 1.001430e+03 2.156300e+02 +8 1437 6.415002e+01 2.594200e+02 +0 1438 -1.102520e+03 2.215500e+02 +7 1438 -9.050800e+02 3.535601e+02 +0 1439 9.251599e+02 2.265901e+02 +5 1439 7.566699e+02 7.925500e+02 +0 1440 9.111101e+02 2.280200e+02 +8 1440 -9.813000e+01 2.875300e+02 +0 1441 7.948301e+02 2.340200e+02 +4 1441 1.037670e+03 3.604600e+02 +0 1442 7.857000e+02 2.344299e+02 +5 1442 6.316000e+02 7.724800e+02 +0 1443 8.958701e+02 2.383800e+02 +5 1443 7.304700e+02 7.971500e+02 +0 1444 7.652900e+02 2.418500e+02 +5 1444 6.127900e+02 7.739100e+02 +0 1445 7.908000e+02 2.540000e+02 +5 1445 6.333600e+02 7.879800e+02 +0 1446 1.541460e+03 2.578900e+02 +3 1446 9.651101e+02 3.586200e+02 +17 1446 -1.016620e+03 5.568900e+02 +0 1447 7.291201e+02 2.656699e+02 +5 1447 5.810300e+02 7.873400e+02 +0 1448 5.661799e+02 2.681500e+02 +8 1448 -6.985700e+02 3.764399e+02 +0 1449 5.622600e+02 2.720601e+02 +8 1449 -7.047400e+02 3.832600e+02 +0 1450 1.694020e+03 2.724600e+02 +8 1450 9.946801e+02 3.543101e+02 +0 1451 1.555660e+03 2.727800e+02 +8 1451 8.060000e+02 3.550400e+02 +0 1452 8.261499e+02 2.769700e+02 +8 1452 -2.395600e+02 3.698900e+02 +0 1453 7.679600e+02 2.968301e+02 +5 1453 6.203800e+02 8.250100e+02 +0 1454 6.995000e+02 3.045100e+02 +5 1454 5.562100e+02 8.142100e+02 +0 1455 1.641270e+03 3.065901e+02 +7 1455 9.507900e+02 4.059600e+02 +0 1456 1.576250e+03 3.066100e+02 +8 1456 8.331000e+02 4.081600e+02 +0 1457 5.810000e+02 3.087500e+02 +8 1457 -6.707900e+02 4.418600e+02 +0 1458 5.169900e+02 3.120200e+02 +5 1458 4.051200e+02 7.866500e+02 +0 1459 1.688220e+03 3.141200e+02 +8 1459 9.847100e+02 4.174800e+02 +0 1460 1.688220e+03 3.141200e+02 +8 1460 9.847100e+02 4.174800e+02 +0 1461 -7.950200e+02 3.151799e+02 +7 1461 -7.852100e+02 4.490801e+02 +0 1462 8.291001e+02 3.320801e+02 +6 1462 -1.323900e+02 2.436300e+02 +8 1462 -2.325800e+02 4.543300e+02 +0 1463 1.603330e+03 3.456200e+02 +8 1463 8.707700e+02 4.665000e+02 +0 1464 1.655660e+03 3.503000e+02 +8 1464 9.420300e+02 4.716300e+02 +0 1465 1.655660e+03 3.503000e+02 +8 1465 9.420300e+02 4.716300e+02 +0 1466 7.633101e+02 3.553201e+02 +5 1466 6.106801e+02 8.703900e+02 +8 1466 -3.290500e+02 4.922200e+02 +0 1467 6.347200e+02 3.592000e+02 +8 1467 -5.740100e+02 5.168900e+02 +0 1468 1.707400e+03 3.663201e+02 +8 1468 1.012750e+03 4.947100e+02 +0 1469 1.707400e+03 3.663201e+02 +8 1469 1.012750e+03 4.947100e+02 +0 1470 6.999600e+02 3.665601e+02 +5 1470 5.619301e+02 8.728400e+02 +0 1471 5.407200e+02 3.829800e+02 +5 1471 4.145300e+02 8.436400e+02 +8 1471 -7.409500e+02 5.644299e+02 +0 1472 4.705500e+02 3.849700e+02 +5 1472 3.636700e+02 8.357700e+02 +0 1473 5.804500e+02 3.921200e+02 +5 1473 4.461000e+02 8.571899e+02 +0 1474 5.112700e+02 4.032400e+02 +8 1474 -7.915000e+02 5.994800e+02 +0 1475 1.633360e+03 4.034500e+02 +8 1475 9.237900e+02 5.431000e+02 +0 1476 6.364199e+02 4.184399e+02 +8 1476 -5.658100e+02 6.113101e+02 +0 1477 6.029299e+02 4.738700e+02 +8 1477 -6.270300e+02 7.048700e+02 +0 1478 6.029299e+02 4.738700e+02 +8 1478 -6.270300e+02 7.048700e+02 +0 1479 5.939600e+02 4.741000e+02 +5 1479 4.493199e+02 9.227000e+02 +0 1480 -1.062310e+03 4.829700e+02 +7 1480 -8.875200e+02 5.600701e+02 +19 1480 5.073400e+02 5.198700e+02 +0 1481 5.412200e+02 4.856000e+02 +8 1481 -7.349400e+02 7.300100e+02 +0 1482 5.152600e+02 4.856100e+02 +8 1482 -7.792100e+02 7.323400e+02 +0 1483 5.100500e+02 4.902900e+02 +5 1483 3.826700e+02 9.212700e+02 +8 1483 -7.855000e+02 7.417400e+02 +0 1484 4.275701e+02 5.075601e+02 +5 1484 3.182700e+02 9.221300e+02 +0 1485 -8.323200e+02 5.162500e+02 +7 1485 -7.577400e+02 5.954800e+02 +0 1486 -1.498680e+03 8.589700e+02 +4 1486 -2.132000e+02 6.397400e+02 +0 1487 1.219480e+03 -2.031300e+02 +8 1487 -6.360800e+02 -4.206801e+02 +0 1488 8.513000e+02 1.295801e+02 +8 1488 -1.984900e+02 1.379800e+02 +0 1489 9.304600e+02 1.327300e+02 +8 1489 -6.389001e+01 1.383800e+02 +0 1490 1.140870e+03 1.416599e+02 +6 1490 1.872000e+02 -6.953998e+01 +8 1490 3.003000e+02 1.358900e+02 +0 1491 9.672300e+02 1.429299e+02 +8 1491 1.050049e+00 1.515100e+02 +0 1492 9.231499e+02 1.453101e+02 +8 1492 -7.691998e+01 1.575700e+02 +0 1493 8.119900e+02 1.667400e+02 +5 1493 6.621899e+02 7.249500e+02 +0 1494 9.185801e+02 2.065701e+02 +5 1494 7.535801e+02 7.763900e+02 +0 1495 1.011560e+03 2.192700e+02 +8 1495 7.871997e+01 2.638600e+02 +0 1496 1.513550e+03 2.250300e+02 +8 1496 7.493800e+02 2.838400e+02 +0 1497 1.515480e+03 2.275601e+02 +8 1497 7.515200e+02 2.876100e+02 +0 1498 1.577320e+03 2.396200e+02 +8 1498 8.348000e+02 3.066700e+02 +0 1499 8.453999e+02 2.576799e+02 +8 1499 -2.070800e+02 3.379600e+02 +0 1500 9.908000e+02 2.697600e+02 +8 1500 5.340002e+01 3.394700e+02 +0 1501 8.456299e+02 2.953301e+02 +8 1501 -2.079100e+02 3.973000e+02 +0 1502 8.615500e+02 3.061100e+02 +8 1502 -1.810000e+02 4.121600e+02 +0 1503 5.758301e+02 3.138500e+02 +5 1503 4.502900e+02 7.971899e+02 +0 1504 1.545220e+03 3.351500e+02 +8 1504 7.916100e+02 4.512400e+02 +0 1505 1.548010e+03 3.402400e+02 +8 1505 7.954399e+02 4.587400e+02 +0 1506 1.547960e+03 3.446699e+02 +8 1506 7.952800e+02 4.652100e+02 +0 1507 5.625300e+02 3.564000e+02 +6 1507 -5.025000e+02 3.656400e+02 +8 1507 -7.030000e+02 5.189500e+02 +0 1508 1.597280e+03 3.623700e+02 +8 1508 8.620200e+02 4.919399e+02 +0 1509 7.383999e+02 3.704000e+02 +5 1509 5.905500e+02 8.799100e+02 +0 1510 4.436001e+02 3.760000e+02 +8 1510 -9.066100e+02 5.598500e+02 +0 1511 1.683600e+03 4.068101e+02 +8 1511 9.927800e+02 5.463000e+02 +0 1512 6.231599e+02 4.616000e+02 +8 1512 -5.850800e+02 6.800601e+02 +1 1513 8.904600e+02 -2.590200e+02 +2 1513 6.981200e+02 -1.393000e+02 +1 1514 -1.101110e+03 7.304200e+02 +2 1514 -3.667500e+02 3.817800e+02 +7 1514 1.874301e+02 5.097700e+02 +9 1514 -3.877600e+02 4.270601e+02 +10 1514 -2.909399e+02 -2.337500e+02 +11 1514 2.678600e+02 3.562800e+02 +1 1515 -1.101110e+03 7.304200e+02 +2 1515 -3.667500e+02 3.817800e+02 +4 1515 8.369800e+02 4.532600e+02 +5 1515 3.560699e+02 8.669800e+02 +7 1515 1.874301e+02 5.097700e+02 +10 1515 -2.909399e+02 -2.337500e+02 +11 1515 2.678600e+02 3.562800e+02 +12 1515 -9.177500e+02 -3.314800e+02 +18 1515 -5.129800e+02 1.513500e+02 +1 1516 9.544600e+02 -2.159200e+02 +2 1516 7.355800e+02 -1.156100e+02 +3 1516 1.009090e+03 -1.125000e+02 +7 1516 8.943501e+02 2.055200e+02 +16 1516 9.583300e+02 2.518100e+02 +1 1517 9.466299e+02 -1.245400e+02 +2 1517 7.321500e+02 -6.250000e+01 +1 1518 -1.242590e+03 -1.101400e+02 +2 1518 -4.124000e+02 -8.515997e+01 +7 1518 1.555601e+02 2.280901e+02 +9 1518 -4.211400e+02 7.067004e+01 +10 1518 -3.166899e+02 -4.892700e+02 +11 1518 2.351100e+02 1.088000e+01 +1 1519 7.338201e+02 1.962000e+01 +2 1519 6.059600e+02 3.612000e+01 +3 1519 7.398199e+02 1.185400e+02 +17 1519 -1.200470e+03 3.868201e+02 +1 1520 -9.225900e+02 1.030901e+02 +2 1520 -2.829100e+02 4.620001e+01 +7 1520 2.443300e+02 3.068201e+02 +10 1520 -2.416500e+02 -4.170699e+02 +1 1521 -7.756800e+02 1.432400e+02 +2 1521 -2.381700e+02 8.659998e+01 +7 1521 2.831200e+02 3.314900e+02 +11 1521 3.654399e+02 1.515900e+02 +12 1521 -8.309400e+02 -5.041700e+02 +1 1522 1.301970e+03 2.003301e+02 +7 1522 1.016740e+03 3.560500e+02 +9 1522 6.256001e+02 2.386100e+02 +13 1522 1.286130e+03 5.081100e+02 +17 1522 -6.903600e+02 4.920000e+02 +1 1523 -9.225700e+02 5.572300e+02 +7 1523 2.407400e+02 4.624700e+02 +9 1523 -3.253199e+02 3.702000e+02 +10 1523 -2.453000e+02 -2.767900e+02 +1 1524 -1.220660e+03 6.168600e+02 +5 1524 3.220800e+02 8.169700e+02 +8 1524 -9.563800e+02 5.505300e+02 +1 1525 -1.097190e+03 -2.763600e+02 +2 1525 -3.448300e+02 -1.698600e+02 +9 1525 -3.666300e+02 7.680054e+00 +11 1525 2.847100e+02 -4.690002e+01 +12 1525 -9.155100e+02 -6.632400e+02 +20 1525 -4.300800e+02 -2.948700e+02 +1 1526 7.460901e+02 -2.575900e+02 +2 1526 6.104600e+02 -1.280500e+02 +6 1526 6.906600e+02 -2.319300e+02 +1 1527 7.430200e+02 -1.475800e+02 +2 1527 6.091000e+02 -6.403003e+01 +1 1528 8.834099e+02 -1.242800e+02 +2 1528 6.953101e+02 -6.140002e+01 +3 1528 9.282600e+02 -2.297998e+01 +1 1529 8.834099e+02 -1.242800e+02 +2 1529 6.953101e+02 -6.140002e+01 +3 1529 9.282600e+02 -2.297998e+01 +1 1530 7.299099e+02 2.280200e+02 +3 1530 7.335500e+02 3.365900e+02 +1 1531 9.684600e+02 2.263301e+02 +6 1531 8.391300e+02 1.241400e+02 +1 1532 8.745000e+02 3.385801e+02 +6 1532 7.765699e+02 2.045600e+02 +1 1533 -1.101670e+03 3.761899e+02 +2 1533 -3.592500e+02 1.846400e+02 +4 1533 8.384600e+02 3.604900e+02 +5 1533 3.750699e+02 7.440100e+02 +7 1533 1.906899e+02 3.909900e+02 +8 1533 -8.661200e+02 3.738101e+02 +9 1533 -3.802800e+02 2.764099e+02 +10 1533 -2.866400e+02 -3.405500e+02 +11 1533 2.724900e+02 2.113600e+02 +12 1533 -9.167900e+02 -4.492400e+02 +18 1533 -5.110500e+02 5.681006e+01 +1 1534 -1.278220e+03 4.285000e+02 +4 1534 7.935500e+02 3.687600e+02 +9 1534 -4.446200e+02 2.909199e+02 +12 1534 -9.656700e+02 -4.356500e+02 +1 1535 -1.042680e+03 4.613500e+02 +2 1535 -3.367200e+02 2.308000e+02 +4 1535 8.520200e+02 3.832500e+02 +5 1535 3.892300e+02 7.780701e+02 +7 1535 2.085900e+02 4.205200e+02 +8 1535 -8.256400e+02 4.390500e+02 +10 1535 -2.721899e+02 -3.149100e+02 +12 1535 -8.995600e+02 -4.210200e+02 +1 1536 -1.264790e+03 6.643600e+02 +2 1536 -4.363400e+02 3.386600e+02 +5 1536 3.061500e+02 8.287600e+02 +6 1536 -7.588100e+02 4.526500e+02 +7 1536 1.415900e+02 4.818600e+02 +9 1536 -4.427500e+02 3.904399e+02 +10 1536 -3.313600e+02 -2.585500e+02 +11 1536 2.135000e+02 3.206400e+02 +1 1537 -1.190900e+03 6.932700e+02 +5 1537 3.254000e+02 8.438400e+02 +8 1537 -9.381000e+02 6.073500e+02 +1 1538 -1.414780e+03 7.193600e+02 +2 1538 -5.108300e+02 3.636200e+02 +5 1538 2.544399e+02 8.348900e+02 +7 1538 9.643005e+01 4.954099e+02 +9 1538 -4.998300e+02 4.095400e+02 +10 1538 -3.703400e+02 -2.448600e+02 +11 1538 1.602600e+02 3.384300e+02 +12 1538 -1.008010e+03 -3.429100e+02 +16 1538 3.081700e+02 4.625300e+02 +1 1539 8.688201e+02 -3.550200e+02 +2 1539 6.868600e+02 -1.923700e+02 +1 1540 8.975901e+02 -3.231300e+02 +2 1540 7.016700e+02 -1.753600e+02 +3 1540 9.454399e+02 -2.222000e+02 +1 1541 1.447660e+03 -3.106500e+02 +7 1541 1.058950e+03 1.708201e+02 +9 1541 6.801499e+02 1.718005e+01 +12 1541 -7.944995e+01 -6.673300e+02 +18 1541 1.444900e+02 -1.182900e+02 +20 1541 1.321899e+02 -2.964200e+02 +1 1542 9.896799e+02 -1.792800e+02 +2 1542 7.565601e+02 -9.722998e+01 +5 1542 1.203630e+03 6.870400e+02 +7 1542 9.052800e+02 2.202000e+02 +8 1542 8.303900e+02 -3.003998e+01 +16 1542 9.671400e+02 2.637600e+02 +17 1542 -9.550800e+02 1.793000e+02 +1 1543 3.471801e+02 -1.295000e+02 +2 1543 6.787000e+01 1.683200e+02 +11 1543 7.064301e+02 3.438700e+02 +13 1543 -1.563300e+02 6.245601e+02 +1 1544 -5.988300e+02 -7.476001e+01 +6 1544 -2.661800e+02 -7.220001e+01 +1 1545 -1.204360e+03 -6.420996e+01 +2 1545 -3.957500e+02 -5.862000e+01 +4 1545 8.128999e+02 2.464900e+02 +7 1545 1.657200e+02 2.454500e+02 +9 1545 -4.073300e+02 9.093994e+01 +10 1545 -3.078000e+02 -4.734900e+02 +11 1545 2.469301e+02 3.294000e+01 +12 1545 -9.458300e+02 -5.975601e+02 +18 1545 -5.306500e+02 -5.856006e+01 +1 1546 -1.280900e+03 -6.310999e+01 +4 1546 7.943201e+02 2.454700e+02 +1 1547 -1.438460e+03 -2.622998e+01 +6 1547 -8.981300e+02 -1.385999e+01 +1 1548 -5.456000e+02 6.744995e+01 +2 1548 -1.601500e+02 6.441998e+01 +7 1548 3.563300e+02 3.214900e+02 +9 1548 -2.060699e+02 1.991100e+02 +11 1548 4.318400e+02 1.373500e+02 +20 1548 -3.372800e+02 -1.924700e+02 +1 1549 7.033401e+02 1.023401e+02 +2 1549 5.846200e+02 9.009998e+01 +17 1549 -1.228110e+03 4.727300e+02 +1 1550 -4.825900e+02 1.157000e+02 +3 1550 -5.284800e+02 2.201400e+02 +6 1550 -1.543400e+02 5.332001e+01 +1 1551 8.256799e+02 1.453800e+02 +2 1551 6.626500e+02 9.846997e+01 +17 1551 -1.103450e+03 4.790801e+02 +1 1552 1.184940e+03 1.604099e+02 +8 1552 9.796000e+02 2.564399e+02 +17 1552 -7.867300e+02 4.594299e+02 +1 1553 1.184940e+03 1.604099e+02 +7 1553 9.753601e+02 3.402600e+02 +8 1553 9.796000e+02 2.564399e+02 +17 1553 -7.867300e+02 4.594299e+02 +1 1554 9.312700e+02 2.975400e+02 +6 1554 8.161500e+02 1.737700e+02 +16 1554 9.576899e+02 4.048600e+02 +17 1554 -1.000180e+03 5.937000e+02 +1 1555 -1.308020e+03 4.533401e+02 +2 1555 -4.570400e+02 2.198900e+02 +4 1555 7.857200e+02 3.749000e+02 +5 1555 3.040500e+02 7.533201e+02 +7 1555 1.296700e+02 4.108600e+02 +9 1555 -4.561700e+02 2.997700e+02 +10 1555 -3.412000e+02 -3.218600e+02 +12 1555 -9.778300e+02 -4.282500e+02 +18 1555 -5.586200e+02 7.265991e+01 +1 1556 -9.359700e+02 4.807500e+02 +2 1556 -2.932400e+02 2.543900e+02 +4 1556 8.844099e+02 3.956300e+02 +5 1556 4.286200e+02 7.977000e+02 +7 1556 2.382000e+02 4.337100e+02 +8 1556 -7.288400e+02 4.634600e+02 +9 1556 -3.282600e+02 3.330901e+02 +1 1557 -1.174790e+03 5.172500e+02 +5 1557 3.452900e+02 7.862600e+02 +8 1557 -9.157100e+02 4.781200e+02 +1 1558 -9.682100e+02 5.857900e+02 +4 1558 8.743000e+02 4.221300e+02 +5 1558 4.102100e+02 8.327400e+02 +7 1558 2.283600e+02 4.681000e+02 +8 1558 -7.563400e+02 5.428600e+02 +9 1558 -3.435400e+02 3.769900e+02 +10 1558 -2.563700e+02 -2.710400e+02 +11 1558 3.117900e+02 3.072800e+02 +12 1558 -8.799100e+02 -3.725900e+02 +20 1558 -4.098199e+02 -9.650000e+01 +1 1559 -8.653300e+02 6.120500e+02 +3 1559 -8.568400e+02 7.689900e+02 +7 1559 2.583101e+02 4.857100e+02 +10 1559 -2.308199e+02 -2.567100e+02 +1 1560 -8.212400e+02 6.143500e+02 +3 1560 -8.191400e+02 7.699700e+02 +1 1561 -1.176980e+03 6.531700e+02 +2 1561 -3.987200e+02 3.357000e+02 +4 1561 8.178999e+02 4.291400e+02 +5 1561 3.354200e+02 8.315500e+02 +6 1561 -6.997000e+02 4.425100e+02 +7 1561 1.655500e+02 4.806500e+02 +8 1561 -9.230800e+02 5.773300e+02 +9 1561 -4.116200e+02 3.893800e+02 +10 1561 -3.094800e+02 -2.597100e+02 +11 1561 2.433400e+02 3.207900e+02 +12 1561 -9.427200e+02 -3.581899e+02 +1 1562 -1.176980e+03 6.531700e+02 +7 1562 1.655500e+02 4.806500e+02 +9 1562 -4.116200e+02 3.893800e+02 +12 1562 -9.427200e+02 -3.581899e+02 +1 1563 -1.149590e+03 6.888800e+02 +2 1563 -3.823600e+02 3.550600e+02 +4 1563 8.248101e+02 4.398900e+02 +5 1563 3.410200e+02 8.470800e+02 +7 1563 1.751400e+02 4.928700e+02 +8 1563 -9.062300e+02 6.075601e+02 +9 1563 -4.003199e+02 4.055400e+02 +10 1563 -3.004600e+02 -2.491500e+02 +11 1563 2.551500e+02 3.355100e+02 +12 1563 -9.287100e+02 -3.482100e+02 +1 1564 -1.365590e+03 7.801100e+02 +2 1564 -4.874300e+02 3.970000e+02 +5 1564 2.663300e+02 8.583900e+02 +6 1564 -8.282000e+02 5.319399e+02 +7 1564 1.112800e+02 5.151500e+02 +9 1564 -4.831400e+02 4.352100e+02 +10 1564 -3.570900e+02 -2.273000e+02 +11 1564 1.786100e+02 3.613700e+02 +12 1564 -9.921900e+02 -3.230100e+02 +18 1564 -5.718600e+02 1.565801e+02 +20 1564 -4.864600e+02 -6.339001e+01 +1 1565 -1.334070e+03 8.045900e+02 +2 1565 -4.728800e+02 4.113200e+02 +5 1565 2.746700e+02 8.700300e+02 +7 1565 1.185800e+02 5.274900e+02 +1 1566 -8.090400e+02 -4.225400e+02 +3 1566 -7.890400e+02 -3.359700e+02 +1 1567 8.719399e+02 -4.059800e+02 +2 1567 6.878600e+02 -2.216800e+02 +3 1567 9.162500e+02 -3.078300e+02 +1 1568 -1.218900e+03 -3.571600e+02 +2 1568 -3.962300e+02 -2.152900e+02 +1 1569 -1.015740e+03 -3.164800e+02 +2 1569 -3.097800e+02 -1.894400e+02 +9 1569 -3.390300e+02 -6.170044e+00 +10 1569 -2.584399e+02 -5.443800e+02 +11 1569 3.105900e+02 -6.069000e+01 +12 1569 -8.922400e+02 -6.751899e+02 +18 1569 -4.894700e+02 -1.207700e+02 +20 1569 -4.153500e+02 -3.027300e+02 +1 1570 -1.177660e+03 -3.117400e+02 +2 1570 -3.798800e+02 -1.904300e+02 +7 1570 1.758700e+02 1.672100e+02 +9 1570 -3.941500e+02 -8.300049e+00 +10 1570 -2.988000e+02 -5.453600e+02 +11 1570 2.591700e+02 -6.258002e+01 +12 1570 -9.377100e+02 -6.765200e+02 +18 1570 -5.236800e+02 -1.215601e+02 +20 1570 -4.453600e+02 -3.037300e+02 +1 1571 -1.229210e+03 -3.111000e+02 +2 1571 -4.046800e+02 -1.912400e+02 +7 1571 1.606899e+02 1.669000e+02 +10 1571 -3.126400e+02 -5.455000e+02 +11 1571 2.416000e+02 -6.344000e+01 +20 1571 -4.553700e+02 -3.038600e+02 +1 1572 -1.263450e+03 -3.106000e+02 +2 1572 -4.185500e+02 -1.916800e+02 +9 1572 -4.242600e+02 -9.880005e+00 +11 1572 2.304100e+02 -6.378003e+01 +18 1572 -5.414600e+02 -1.220800e+02 +1 1573 -1.319480e+03 -3.085699e+02 +7 1573 1.352900e+02 1.667700e+02 +1 1574 -1.129820e+03 -3.055100e+02 +2 1574 -3.579100e+02 -1.861700e+02 +7 1574 1.894301e+02 1.695701e+02 +9 1574 -3.771200e+02 -4.939941e+00 +11 1574 2.755601e+02 -5.940997e+01 +12 1574 -9.238500e+02 -6.739900e+02 +18 1574 -5.131500e+02 -1.192900e+02 +20 1574 -4.355699e+02 -3.020300e+02 +1 1575 8.870801e+02 -2.938000e+02 +2 1575 6.973000e+02 -1.579600e+02 +3 1575 9.354800e+02 -1.934301e+02 +6 1575 7.732700e+02 -2.576800e+02 +1 1576 -9.063500e+02 -2.886400e+02 +2 1576 -2.704400e+02 -1.711500e+02 +9 1576 -3.072300e+02 9.199951e+00 +10 1576 -2.339900e+02 -5.339900e+02 +11 1576 3.407500e+02 -4.578998e+01 +12 1576 -8.631400e+02 -6.626500e+02 +18 1576 -4.685200e+02 -1.112000e+02 +20 1576 -3.973000e+02 -2.945100e+02 +1 1577 1.076400e+03 -2.868400e+02 +5 1577 1.234010e+03 6.478800e+02 +6 1577 9.067900e+02 -2.574500e+02 +7 1577 9.314099e+02 1.814600e+02 +8 1577 8.891899e+02 -1.186100e+02 +16 1577 9.871500e+02 2.329000e+02 +1 1578 1.422860e+03 -2.815100e+02 +7 1578 1.052060e+03 1.822700e+02 +10 1578 4.672200e+02 -5.183101e+02 +1 1579 1.379720e+03 -2.808700e+02 +7 1579 1.036820e+03 1.823301e+02 +9 1579 6.527800e+02 3.056006e+01 +17 1579 -6.391600e+02 9.381006e+01 +1 1580 -1.204870e+03 -2.796100e+02 +2 1580 -3.925500e+02 -1.697600e+02 +6 1580 -7.491200e+02 -1.911300e+02 +7 1580 1.676600e+02 1.790601e+02 +9 1580 -4.041300e+02 3.089966e+00 +11 1580 2.497700e+02 -4.748999e+01 +12 1580 -9.457800e+02 -6.632100e+02 +18 1580 -5.300300e+02 -1.115000e+02 +20 1580 -4.506500e+02 -2.952600e+02 +1 1581 -1.204870e+03 -2.796100e+02 +6 1581 -7.491200e+02 -1.911300e+02 +1 1582 -1.179590e+03 -2.770000e+02 +2 1582 -3.817300e+02 -1.724800e+02 +7 1582 1.750601e+02 1.775701e+02 +12 1582 -9.386600e+02 -6.649700e+02 +1 1583 -1.179590e+03 -2.770000e+02 +2 1583 -3.817300e+02 -1.724800e+02 +7 1583 1.750601e+02 1.775701e+02 +9 1583 -3.956801e+02 3.920044e+00 +11 1583 2.578400e+02 -4.975000e+01 +12 1583 -9.386600e+02 -6.649700e+02 +18 1583 -5.245900e+02 -1.132700e+02 +20 1583 -4.461600e+02 -2.962600e+02 +1 1584 -1.321620e+03 -2.708400e+02 +7 1584 1.337400e+02 1.778201e+02 +9 1584 -4.464700e+02 4.709961e+00 +10 1584 -3.372700e+02 -5.340000e+02 +12 1584 -9.800000e+02 -6.651899e+02 +18 1584 -5.569100e+02 -1.126801e+02 +20 1584 -4.739900e+02 -2.956600e+02 +1 1585 -1.321620e+03 -2.708400e+02 +2 1585 -4.478000e+02 -1.722400e+02 +7 1585 1.337400e+02 1.778201e+02 +9 1585 -4.464700e+02 4.709961e+00 +11 1585 2.099200e+02 -4.915002e+01 +18 1585 -5.569100e+02 -1.126801e+02 +20 1585 -4.739900e+02 -2.956600e+02 +1 1586 1.468270e+03 -2.532000e+02 +7 1586 1.068500e+03 1.916000e+02 +9 1586 6.894500e+02 4.151001e+01 +10 1586 4.804800e+02 -5.094500e+02 +12 1586 -7.119995e+01 -6.478900e+02 +17 1586 -5.702900e+02 1.133300e+02 +18 1586 1.513300e+02 -1.032900e+02 +20 1586 1.373500e+02 -2.834200e+02 +1 1587 1.427160e+03 -2.371000e+02 +7 1587 1.053920e+03 1.977000e+02 +9 1587 6.730300e+02 4.814001e+01 +10 1587 4.681201e+02 -5.041200e+02 +17 1587 -6.031300e+02 1.268199e+02 +18 1587 1.406600e+02 -9.956006e+01 +1 1588 -8.059200e+02 -1.334100e+02 +2 1588 -2.493300e+02 -7.733002e+01 +9 1588 -2.877000e+02 8.293994e+01 +10 1588 -2.162800e+02 -4.827800e+02 +11 1588 3.579000e+02 2.500000e+01 +13 1588 -1.665500e+03 7.869995e+01 +18 1588 -4.544700e+02 -6.533997e+01 +1 1589 2.796200e+02 -1.316899e+02 +2 1589 -4.239990e+00 1.629300e+02 +6 1589 5.825100e+02 -1.592900e+02 +11 1589 6.473199e+02 3.364800e+02 +1 1590 1.286790e+03 -1.268199e+02 +7 1590 1.009650e+03 2.363700e+02 +10 1590 4.283899e+02 -4.720400e+02 +18 1590 1.081801e+02 -6.937000e+01 +1 1591 -5.823200e+02 -1.225000e+02 +2 1591 -1.762400e+02 -5.110999e+01 +3 1591 -6.061400e+02 -2.265002e+01 +7 1591 3.422100e+02 2.499700e+02 +9 1591 -2.239600e+02 1.088700e+02 +11 1591 4.150000e+02 5.019000e+01 +12 1591 -7.819600e+02 -5.845000e+02 +20 1591 -3.494399e+02 -2.411700e+02 +1 1592 -8.252800e+02 -1.036801e+02 +2 1592 -2.516100e+02 -6.175000e+01 +7 1592 2.723300e+02 2.437300e+02 +9 1592 -2.922400e+02 9.400000e+01 +10 1592 -2.199100e+02 -4.744000e+02 +11 1592 3.491000e+02 3.540997e+01 +12 1592 -8.427100e+02 -5.952200e+02 +13 1592 -1.680370e+03 1.174000e+02 +18 1592 -4.555000e+02 -5.820996e+01 +1 1593 -8.726800e+02 -9.518005e+01 +4 1593 9.041201e+02 2.457200e+02 +5 1593 4.851500e+02 6.031200e+02 +7 1593 2.598800e+02 2.441799e+02 +9 1593 -2.993400e+02 9.357996e+01 +12 1593 -8.545400e+02 -5.951300e+02 +18 1593 -4.632900e+02 -5.809998e+01 +1 1594 -8.726800e+02 -9.518005e+01 +7 1594 2.598800e+02 2.441799e+02 +12 1594 -8.545400e+02 -5.951300e+02 +1 1595 9.574500e+02 -6.843005e+01 +2 1595 7.373800e+02 -3.275000e+01 +3 1595 1.014000e+03 3.647998e+01 +17 1595 -9.830600e+02 2.772100e+02 +1 1596 -1.150300e+03 -6.646997e+01 +2 1596 -3.711200e+02 -5.815002e+01 +4 1596 8.262300e+02 2.463500e+02 +7 1596 1.818500e+02 2.456300e+02 +9 1596 -3.881899e+02 9.209998e+01 +10 1596 -2.941600e+02 -4.731500e+02 +11 1596 2.651300e+02 3.389001e+01 +18 1596 -5.183800e+02 -5.803003e+01 +1 1597 -1.150300e+03 -6.646997e+01 +7 1597 1.818500e+02 2.456300e+02 +9 1597 -3.881899e+02 9.209998e+01 +10 1597 -2.941600e+02 -4.731500e+02 +11 1597 2.651300e+02 3.389001e+01 +18 1597 -5.183800e+02 -5.803003e+01 +1 1598 -9.039000e+02 -6.288000e+01 +3 1598 -8.785500e+02 4.715002e+01 +1 1599 -3.413199e+02 -4.860999e+01 +3 1599 -4.200500e+02 4.479999e+01 +1 1600 -1.088850e+03 -4.273999e+01 +2 1600 -3.397000e+02 -4.434998e+01 +3 1600 -1.058880e+03 7.096002e+01 +5 1600 4.022800e+02 6.025601e+02 +7 1600 2.001300e+02 2.539199e+02 +9 1600 -3.654399e+02 1.030400e+02 +10 1600 -2.768700e+02 -4.651200e+02 +18 1600 -5.050100e+02 -5.196997e+01 +1 1601 -1.132390e+03 -3.855005e+01 +2 1601 -3.622800e+02 -4.333002e+01 +4 1601 8.308701e+02 2.534900e+02 +5 1601 3.865500e+02 6.008600e+02 +7 1601 1.868000e+02 2.541599e+02 +9 1601 -3.815900e+02 1.032500e+02 +10 1601 -2.891700e+02 -4.643700e+02 +11 1601 2.719100e+02 4.479999e+01 +12 1601 -9.245200e+02 -5.863900e+02 +20 1601 -4.365699e+02 -2.429200e+02 +1 1602 -1.283330e+03 -3.121997e+01 +2 1602 -4.293400e+02 -4.306000e+01 +4 1602 7.932000e+02 2.535701e+02 +5 1602 3.384600e+02 5.938800e+02 +7 1602 1.438300e+02 2.544500e+02 +9 1602 -4.333700e+02 1.020699e+02 +10 1602 -3.275400e+02 -4.642900e+02 +11 1602 2.219600e+02 4.327002e+01 +12 1602 -9.680200e+02 -5.868101e+02 +18 1602 -5.468800e+02 -5.131995e+01 +20 1602 -4.653199e+02 -2.432300e+02 +1 1603 -4.649301e+02 -2.944995e+01 +2 1603 -1.473800e+02 2.044000e+01 +7 1603 3.818500e+02 2.944500e+02 +9 1603 -1.961300e+02 1.710300e+02 +10 1603 -1.425000e+02 -4.279200e+02 +11 1603 4.408500e+02 1.093700e+02 +12 1603 -7.458200e+02 -5.360500e+02 +13 1603 -1.332630e+03 3.088101e+02 +20 1603 -3.326801e+02 -2.076400e+02 +1 1604 -1.201150e+03 -6.940002e+00 +2 1604 -3.977400e+02 -3.015002e+01 +4 1604 8.136699e+02 2.604500e+02 +9 1604 -4.089301e+02 1.130100e+02 +10 1604 -3.086500e+02 -4.571400e+02 +12 1604 -9.454300e+02 -5.792600e+02 +18 1604 -5.310400e+02 -4.573999e+01 +20 1604 -4.517500e+02 -2.374800e+02 +1 1605 -1.201150e+03 -6.940002e+00 +2 1605 -3.977400e+02 -3.015002e+01 +4 1605 8.136699e+02 2.604500e+02 +5 1605 3.635699e+02 6.068300e+02 +7 1605 1.656700e+02 2.628800e+02 +10 1605 -3.086500e+02 -4.571400e+02 +20 1605 -4.517500e+02 -2.374800e+02 +1 1606 -1.287460e+03 -6.369995e+00 +2 1606 -4.371800e+02 -2.940997e+01 +4 1606 7.923301e+02 2.596799e+02 +5 1606 3.362000e+02 6.017900e+02 +7 1606 1.407900e+02 2.626799e+02 +9 1606 -4.391899e+02 1.122900e+02 +10 1606 -3.306700e+02 -4.571400e+02 +11 1606 2.168000e+02 5.352002e+01 +1 1607 -4.883700e+02 8.150024e+00 +7 1607 3.761500e+02 3.050601e+02 +10 1607 -1.431500e+02 -4.190000e+02 +11 1607 4.445000e+02 1.207800e+02 +12 1607 -7.481000e+02 -5.268500e+02 +13 1607 -1.327880e+03 3.504299e+02 +18 1607 -3.916000e+02 -4.540039e+00 +20 1607 -3.311801e+02 -2.014399e+02 +1 1608 -1.101820e+03 5.976001e+01 +2 1608 -3.512100e+02 1.135999e+01 +4 1608 8.397100e+02 2.792000e+02 +5 1608 3.935601e+02 6.365200e+02 +7 1608 1.944600e+02 2.869600e+02 +9 1608 -3.730200e+02 1.449800e+02 +10 1608 -2.827600e+02 -4.344500e+02 +11 1608 2.800200e+02 8.497998e+01 +20 1608 -4.319301e+02 -2.205699e+02 +1 1609 -1.101820e+03 5.976001e+01 +2 1609 -3.512100e+02 1.135999e+01 +4 1609 8.397100e+02 2.792000e+02 +5 1609 3.935601e+02 6.365200e+02 +7 1609 1.944600e+02 2.869600e+02 +11 1609 2.800200e+02 8.497998e+01 +20 1609 -4.319301e+02 -2.205699e+02 +1 1610 -1.193450e+03 1.585901e+02 +2 1610 -3.971600e+02 6.271002e+01 +4 1610 8.149399e+02 3.024900e+02 +7 1610 1.665100e+02 3.176500e+02 +9 1610 -4.087600e+02 1.823500e+02 +10 1610 -3.080100e+02 -4.071200e+02 +11 1610 2.455699e+02 1.211600e+02 +12 1610 -9.437200e+02 -5.239000e+02 +18 1610 -5.302100e+02 -1.569946e+00 +20 1610 -4.506300e+02 -1.995699e+02 +1 1611 1.365380e+03 1.654099e+02 +7 1611 1.040780e+03 3.424800e+02 +9 1611 6.521699e+02 2.226699e+02 +12 1611 -9.846997e+01 -5.062900e+02 +13 1611 1.370660e+03 4.538800e+02 +17 1611 -6.414301e+02 4.607100e+02 +18 1611 1.306400e+02 9.339966e+00 +20 1611 1.184000e+02 -1.865900e+02 +1 1612 -8.136600e+02 1.804199e+02 +5 1612 4.973400e+02 7.097400e+02 +9 1612 -2.939200e+02 2.159900e+02 +10 1612 -2.197600e+02 -3.869301e+02 +11 1612 3.538400e+02 1.528000e+02 +12 1612 -8.399100e+02 -4.980200e+02 +18 1612 -4.560200e+02 1.760999e+01 +20 1612 -3.860200e+02 -1.825800e+02 +1 1613 -1.167340e+03 2.019099e+02 +2 1613 -3.800700e+02 8.554999e+01 +5 1613 3.637600e+02 6.790601e+02 +9 1613 -3.976000e+02 2.002800e+02 +10 1613 -2.983500e+02 -3.939700e+02 +11 1613 2.580100e+02 1.381300e+02 +12 1613 -9.315400e+02 -5.089399e+02 +20 1613 -4.435300e+02 -1.903800e+02 +1 1614 -1.302340e+03 2.166699e+02 +2 1614 -4.480800e+02 9.137000e+01 +4 1614 7.879900e+02 3.151500e+02 +5 1614 3.191600e+02 6.744500e+02 +6 1614 -8.003400e+02 1.502800e+02 +7 1614 1.344301e+02 3.346200e+02 +9 1614 -4.484600e+02 2.028401e+02 +10 1614 -3.368700e+02 -3.916500e+02 +11 1614 2.082300e+02 1.410500e+02 +20 1614 -4.716899e+02 -1.881100e+02 +1 1615 7.653000e+02 2.273201e+02 +2 1615 6.246801e+02 1.613200e+02 +3 1615 7.690300e+02 3.314800e+02 +12 1615 -2.776500e+02 -4.586500e+02 +17 1615 -1.170800e+03 5.809800e+02 +1 1616 1.268210e+03 2.430100e+02 +7 1616 1.008570e+03 3.710300e+02 +12 1616 -1.283600e+02 -4.790400e+02 +1 1617 9.360000e+02 2.439299e+02 +2 1617 7.286400e+02 1.486700e+02 +3 1617 9.899500e+02 3.565000e+02 +6 1617 8.178600e+02 1.344800e+02 +17 1617 -9.951200e+02 5.535400e+02 +1 1618 -6.928100e+02 2.943700e+02 +3 1618 -6.994800e+02 4.182700e+02 +6 1618 -3.355600e+02 1.864200e+02 +7 1618 3.088400e+02 3.916899e+02 +10 1618 -1.926500e+02 -3.407800e+02 +11 1618 3.871500e+02 2.208200e+02 +12 1618 -8.051400e+02 -4.445800e+02 +18 1618 -4.315400e+02 6.078003e+01 +20 1618 -3.652700e+02 -1.455601e+02 +1 1619 -9.696500e+02 3.342600e+02 +5 1619 4.244301e+02 7.430000e+02 +8 1619 -7.554900e+02 3.507800e+02 +1 1620 -1.144370e+03 4.060500e+02 +8 1620 -8.995100e+02 3.946899e+02 +1 1621 -1.144370e+03 4.060500e+02 +5 1621 3.585699e+02 7.502000e+02 +8 1621 -8.995100e+02 3.946899e+02 +1 1622 -5.871300e+02 4.495200e+02 +6 1622 -2.075700e+02 2.811500e+02 +1 1623 8.863501e+02 5.248400e+02 +3 1623 7.777000e+02 6.120900e+02 +17 1623 -1.114280e+03 9.941899e+02 +1 1624 -1.373400e+03 5.444200e+02 +4 1624 7.685400e+02 3.951500e+02 +5 1624 2.778600e+02 7.776400e+02 +7 1624 1.097200e+02 4.377500e+02 +9 1624 -4.791100e+02 3.350400e+02 +10 1624 -3.585200e+02 -2.971700e+02 +12 1624 -9.980300e+02 -4.011100e+02 +16 1624 3.196801e+02 4.187700e+02 +20 1624 -4.871000e+02 -1.171500e+02 +1 1625 -7.912000e+02 6.763800e+02 +2 1625 -2.506000e+02 3.953900e+02 +7 1625 2.762200e+02 5.197300e+02 +9 1625 -2.924301e+02 4.486799e+02 +12 1625 -8.318600e+02 -3.160800e+02 +18 1625 -4.520300e+02 1.626200e+02 +20 1625 -3.821801e+02 -5.794995e+01 +1 1626 -1.410600e+03 6.755800e+02 +2 1626 -5.123500e+02 3.405100e+02 +6 1626 -8.595800e+02 4.612000e+02 +7 1626 9.622998e+01 4.819900e+02 +9 1626 -4.997900e+02 3.920500e+02 +10 1626 -3.712500e+02 -2.572800e+02 +11 1626 1.600601e+02 3.212200e+02 +16 1626 3.087800e+02 4.519600e+02 +20 1626 -4.964700e+02 -8.679004e+01 +1 1627 -1.329010e+03 7.732000e+02 +5 1627 2.787200e+02 8.604800e+02 +1 1628 -1.195170e+03 8.700300e+02 +6 1628 -7.066800e+02 5.905800e+02 +1 1629 -1.231110e+03 8.763000e+02 +6 1629 -7.340800e+02 5.955200e+02 +1 1630 -1.233380e+03 9.724600e+02 +6 1630 -7.397000e+02 6.613400e+02 +1 1631 -5.291200e+02 -5.138700e+02 +6 1631 -2.097100e+02 -3.782100e+02 +1 1632 -1.029130e+03 -4.100300e+02 +6 1632 -6.233900e+02 -2.866400e+02 +9 1632 -3.452800e+02 -4.396997e+01 +10 1632 -2.631700e+02 -5.721100e+02 +12 1632 -8.979600e+02 -7.057700e+02 +18 1632 -4.940000e+02 -1.441400e+02 +20 1632 -4.187000e+02 -3.231500e+02 +1 1633 -1.151820e+03 -3.320900e+02 +2 1633 -3.676800e+02 -2.011300e+02 +6 1633 -7.127500e+02 -2.267900e+02 +7 1633 1.831899e+02 1.607500e+02 +9 1633 -3.846899e+02 -1.652002e+01 +11 1633 2.681500e+02 -7.010999e+01 +12 1633 -9.305100e+02 -6.827700e+02 +20 1633 -4.402100e+02 -3.080200e+02 +1 1634 -1.206010e+03 -3.328800e+02 +6 1634 -8.527600e+02 -2.201400e+02 +1 1635 -8.499500e+02 -3.243700e+02 +3 1635 -8.267400e+02 -2.339100e+02 +1 1636 -3.554800e+02 -3.118600e+02 +3 1636 -4.301000e+02 -2.254600e+02 +1 1637 8.194199e+02 -3.005000e+02 +2 1637 6.562200e+02 -1.592600e+02 +6 1637 7.305500e+02 -2.623100e+02 +1 1638 -1.294370e+03 -2.866801e+02 +2 1638 -4.330900e+02 -1.788700e+02 +6 1638 -8.119700e+02 -1.933600e+02 +7 1638 1.420500e+02 1.742400e+02 +9 1638 -4.348500e+02 -7.600098e-01 +10 1638 -3.291300e+02 -5.384900e+02 +11 1638 2.205100e+02 -5.504999e+01 +18 1638 -5.497800e+02 -1.160900e+02 +20 1638 -4.676600e+02 -2.991000e+02 +1 1639 -1.348290e+03 -2.862200e+02 +2 1639 -4.583100e+02 -1.798100e+02 +6 1639 -8.486600e+02 -1.919800e+02 +11 1639 2.019500e+02 -5.545001e+01 +20 1639 -4.788900e+02 -2.994000e+02 +1 1640 9.418301e+02 -1.967500e+02 +2 1640 7.284399e+02 -1.035600e+02 +3 1640 9.925300e+02 -1.041900e+02 +1 1641 2.807200e+02 -1.913000e+02 +2 1641 -2.500000e+00 1.034300e+02 +3 1641 -7.721997e+01 -1.219200e+02 +9 1641 7.566003e+01 3.517900e+02 +10 1641 8.581006e+01 -3.700800e+02 +11 1641 6.431500e+02 2.804400e+02 +13 1641 -3.408800e+02 4.602100e+02 +1 1642 1.304320e+03 -1.512800e+02 +7 1642 1.016960e+03 2.279000e+02 +10 1642 4.346699e+02 -4.791100e+02 +18 1642 1.123300e+02 -7.555005e+01 +20 1642 1.038400e+02 -2.594100e+02 +1 1643 -3.743400e+02 -1.471600e+02 +2 1643 -1.200000e+02 -4.679999e+01 +3 1643 -4.461900e+02 -5.884998e+01 +18 1643 -3.736600e+02 -4.162000e+01 +1 1644 8.445200e+02 -1.263300e+02 +2 1644 6.729301e+02 -5.987000e+01 +3 1644 8.834700e+02 -2.757001e+01 +1 1645 -1.148010e+03 -1.225800e+02 +2 1645 -3.696900e+02 -8.842999e+01 +4 1645 8.273101e+02 2.326799e+02 +7 1645 1.825601e+02 2.279900e+02 +9 1645 -3.868000e+02 6.928003e+01 +10 1645 -2.932400e+02 -4.890200e+02 +11 1645 2.661300e+02 1.240002e+01 +12 1645 -9.296800e+02 -6.131000e+02 +18 1645 -5.182800e+02 -7.230005e+01 +1 1646 -1.174880e+03 -1.209301e+02 +7 1646 1.737600e+02 2.286500e+02 +11 1646 2.563101e+02 1.263000e+01 +18 1646 -5.255200e+02 -7.175000e+01 +20 1646 -4.462600e+02 -2.608000e+02 +1 1647 -1.199140e+03 -1.175300e+02 +2 1647 -3.930200e+02 -8.671002e+01 +4 1647 8.145200e+02 2.330000e+02 +7 1647 1.676801e+02 2.286200e+02 +10 1647 -3.064700e+02 -4.885100e+02 +11 1647 2.490500e+02 1.248999e+01 +12 1647 -9.443900e+02 -6.132000e+02 +18 1647 -5.296400e+02 -7.206995e+01 +1 1648 -1.199140e+03 -1.175300e+02 +2 1648 -3.930200e+02 -8.671002e+01 +5 1648 3.703700e+02 5.707200e+02 +7 1648 1.676801e+02 2.286200e+02 +9 1648 -4.044900e+02 7.023999e+01 +18 1648 -5.296400e+02 -7.206995e+01 +1 1649 -9.607700e+02 -1.090699e+02 +2 1649 -2.952700e+02 -7.357001e+01 +9 1649 -3.280800e+02 8.243005e+01 +10 1649 -2.495000e+02 -4.810800e+02 +11 1649 3.215900e+02 2.476001e+01 +12 1649 -8.788900e+02 -6.043700e+02 +18 1649 -4.804500e+02 -6.537000e+01 +1 1650 -1.044310e+03 -1.018900e+02 +2 1650 -3.281700e+02 -7.257001e+01 +5 1650 4.215601e+02 5.865900e+02 +10 1650 -2.687500e+02 -4.809600e+02 +11 1650 2.961100e+02 2.513000e+01 +12 1650 -9.012100e+02 -6.049000e+02 +18 1650 -4.973800e+02 -6.500000e+01 +1 1651 -3.468800e+02 -8.700000e+01 +3 1651 -4.250400e+02 4.270020e+00 +1 1652 -5.743800e+02 -7.466003e+01 +2 1652 -1.796900e+02 -2.475000e+01 +3 1652 -6.127200e+02 2.615002e+01 +7 1652 3.405400e+02 2.663500e+02 +9 1652 -2.267800e+02 1.297500e+02 +11 1652 4.133000e+02 7.006000e+01 +12 1652 -7.767400e+02 -5.663400e+02 +20 1652 -3.500300e+02 -2.294800e+02 +1 1653 -5.743800e+02 -7.466003e+01 +5 1653 6.239900e+02 6.444100e+02 +6 1653 -2.407600e+02 -7.359003e+01 +12 1653 -7.767400e+02 -5.663400e+02 +1 1654 -4.868400e+02 -4.533997e+01 +6 1654 -1.664000e+02 -5.584998e+01 +1 1655 7.716399e+02 -2.117999e+01 +2 1655 6.270601e+02 1.240997e+01 +17 1655 -1.166010e+03 3.502800e+02 +1 1656 -1.151100e+03 -1.145001e+01 +2 1656 -3.743200e+02 -2.884998e+01 +4 1656 8.264900e+02 2.603201e+02 +5 1656 3.804399e+02 6.092700e+02 +9 1656 -3.913900e+02 1.138000e+02 +10 1656 -2.954900e+02 -4.565200e+02 +11 1656 2.622800e+02 5.515997e+01 +20 1656 -4.418600e+02 -2.368300e+02 +1 1657 -1.151100e+03 -1.145001e+01 +4 1657 8.264900e+02 2.603201e+02 +5 1657 3.804399e+02 6.092700e+02 +7 1657 1.804301e+02 2.632100e+02 +10 1657 -2.954900e+02 -4.565200e+02 +11 1657 2.622800e+02 5.515997e+01 +12 1657 -9.307600e+02 -5.772700e+02 +18 1657 -5.198900e+02 -4.432996e+01 +20 1657 -4.418600e+02 -2.368300e+02 +1 1658 -8.478200e+02 5.789978e+00 +7 1658 2.640500e+02 2.814700e+02 +10 1658 -2.261700e+02 -4.401300e+02 +11 1658 3.469301e+02 8.194000e+01 +12 1658 -8.492400e+02 -5.586000e+02 +18 1658 -4.613400e+02 -2.856995e+01 +1 1659 1.083530e+03 1.971002e+01 +6 1659 9.175699e+02 -3.259003e+01 +1 1660 1.083530e+03 1.971002e+01 +6 1660 9.175699e+02 -3.259003e+01 +1 1661 -6.725800e+02 2.151001e+01 +7 1661 3.145200e+02 2.971599e+02 +1 1662 -1.123470e+03 4.020996e+01 +2 1662 -3.629600e+02 2.500000e-01 +4 1662 8.335300e+02 2.735701e+02 +5 1662 3.869700e+02 6.275500e+02 +7 1662 1.874600e+02 2.802800e+02 +9 1662 -3.818199e+02 1.360901e+02 +10 1662 -2.889399e+02 -4.411500e+02 +11 1662 2.707500e+02 7.650000e+01 +18 1662 -5.141700e+02 -3.114001e+01 +20 1662 -4.362700e+02 -2.256200e+02 +1 1663 7.890500e+02 8.370996e+01 +3 1663 8.047000e+02 1.859800e+02 +1 1664 9.259399e+02 1.068101e+02 +2 1664 7.213199e+02 6.877002e+01 +3 1664 9.751899e+02 2.147000e+02 +17 1664 -1.010880e+03 4.323201e+02 +1 1665 9.259399e+02 1.068101e+02 +2 1665 7.213199e+02 6.877002e+01 +1 1666 5.610200e+02 1.064199e+02 +3 1666 3.701400e+02 1.866200e+02 +1 1667 -4.123400e+02 1.252500e+02 +3 1667 -4.770700e+02 2.277800e+02 +1 1668 -5.248200e+02 1.320100e+02 +4 1668 1.032160e+03 3.338600e+02 +5 1668 6.375100e+02 7.377500e+02 +1 1669 -5.248200e+02 1.320100e+02 +3 1669 -5.600500e+02 2.367300e+02 +4 1669 1.032160e+03 3.338600e+02 +5 1669 6.375100e+02 7.377500e+02 +7 1669 3.619399e+02 3.461799e+02 +9 1669 -2.073000e+02 2.397100e+02 +11 1669 4.317000e+02 1.752500e+02 +12 1669 -7.603600e+02 -4.868700e+02 +13 1669 -1.377360e+03 5.328700e+02 +18 1669 -4.001801e+02 3.006006e+01 +1 1670 1.381790e+03 1.339099e+02 +7 1670 1.045760e+03 3.306899e+02 +10 1670 4.554900e+02 -3.905699e+02 +12 1670 -9.348999e+01 -5.173900e+02 +13 1670 1.390480e+03 4.083700e+02 +17 1670 -6.289500e+02 4.332200e+02 +18 1670 1.344700e+02 -1.700439e-01 +20 1670 1.218101e+02 -1.946600e+02 +1 1671 -1.168380e+03 1.384199e+02 +2 1671 -3.868900e+02 5.247998e+01 +7 1671 1.729600e+02 3.129099e+02 +9 1671 -4.018800e+02 1.781300e+02 +10 1671 -3.020100e+02 -4.140800e+02 +11 1671 2.530699e+02 1.132300e+02 +12 1671 -9.364500e+02 -5.305601e+02 +18 1671 -5.252400e+02 -6.780029e+00 +20 1671 -4.465000e+02 -2.038800e+02 +1 1672 -1.149090e+03 1.553301e+02 +2 1672 -3.762100e+02 6.217999e+01 +7 1672 1.797900e+02 3.175601e+02 +10 1672 -2.964700e+02 -4.072900e+02 +11 1672 2.607400e+02 1.214000e+02 +12 1672 -9.295700e+02 -5.233700e+02 +1 1673 -1.128320e+03 1.732000e+02 +2 1673 -3.675700e+02 7.229999e+01 +4 1673 8.317600e+02 3.077200e+02 +5 1673 3.777200e+02 6.728201e+02 +7 1673 1.855900e+02 3.236300e+02 +9 1673 -3.870800e+02 1.912000e+02 +10 1673 -2.907000e+02 -4.020200e+02 +11 1673 2.674900e+02 1.286900e+02 +1 1674 8.143101e+02 1.840701e+02 +2 1674 6.560200e+02 1.232300e+02 +3 1674 8.375601e+02 2.895200e+02 +6 1674 7.381300e+02 9.203998e+01 +17 1674 -1.114880e+03 5.179900e+02 +1 1675 -1.352970e+03 1.907500e+02 +4 1675 7.755000e+02 3.075500e+02 +5 1675 3.066600e+02 6.623400e+02 +10 1675 -3.499700e+02 -4.001600e+02 +11 1675 1.889301e+02 1.314700e+02 +12 1675 -9.906000e+02 -5.157800e+02 +18 1675 -5.678700e+02 5.459961e+00 +20 1675 -4.825500e+02 -1.943101e+02 +1 1676 -7.473800e+02 2.506000e+02 +3 1676 -7.501900e+02 3.751899e+02 +6 1676 -3.776200e+02 1.561900e+02 +18 1676 -4.440699e+02 4.591003e+01 +1 1677 1.089200e+03 3.451599e+02 +8 1677 9.071000e+02 4.123600e+02 +16 1677 1.000380e+03 4.155400e+02 +1 1678 -1.303590e+03 3.624700e+02 +5 1678 3.115000e+02 7.237800e+02 +1 1679 8.410701e+02 4.026400e+02 +6 1679 7.541000e+02 2.477600e+02 +1 1680 -1.343670e+03 4.064199e+02 +2 1680 -4.699100e+02 1.927200e+02 +4 1680 7.768701e+02 3.617000e+02 +10 1680 -3.487500e+02 -3.371000e+02 +11 1680 1.919301e+02 2.141300e+02 +12 1680 -9.865300e+02 -4.455300e+02 +16 1680 3.289900e+02 3.851000e+02 +18 1680 -5.651100e+02 6.015002e+01 +1 1681 -1.257800e+03 4.594099e+02 +2 1681 -4.314800e+02 2.255400e+02 +5 1681 3.201400e+02 7.595601e+02 +7 1681 1.451100e+02 4.140300e+02 +8 1681 -9.828900e+02 4.304000e+02 +9 1681 -4.362900e+02 3.059199e+02 +10 1681 -3.270800e+02 -3.191000e+02 +11 1681 2.202000e+02 2.395100e+02 +12 1681 -9.621400e+02 -4.256000e+02 +16 1681 3.475500e+02 4.010601e+02 +18 1681 -5.462300e+02 7.552002e+01 +1 1682 8.166499e+02 5.083800e+02 +2 1682 6.412700e+02 4.224200e+02 +3 1682 7.098500e+02 5.958500e+02 +17 1682 -1.183930e+03 9.849700e+02 +1 1683 8.192600e+02 5.325300e+02 +3 1683 7.134900e+02 6.212500e+02 +17 1683 -1.181620e+03 1.007340e+03 +1 1684 -1.135050e+03 6.110100e+02 +2 1684 -3.756700e+02 3.113700e+02 +4 1684 8.291399e+02 4.202300e+02 +5 1684 3.510000e+02 8.213201e+02 +6 1684 -6.720800e+02 4.138201e+02 +7 1684 1.802400e+02 4.668800e+02 +8 1684 -8.921500e+02 5.497500e+02 +9 1684 -3.951000e+02 3.733000e+02 +10 1684 -2.956899e+02 -2.720601e+02 +11 1684 2.600800e+02 3.041200e+02 +12 1684 -9.244600e+02 -3.732700e+02 +1 1685 -1.313460e+03 6.331000e+02 +2 1685 -4.626100e+02 3.181800e+02 +5 1685 2.911700e+02 8.126500e+02 +6 1685 -7.956000e+02 4.316500e+02 +7 1685 1.260000e+02 4.691799e+02 +9 1685 -4.622900e+02 3.747500e+02 +10 1685 -3.441899e+02 -2.687900e+02 +11 1685 1.962500e+02 3.058300e+02 +16 1685 3.327300e+02 4.439100e+02 +18 1685 -5.604200e+02 1.199000e+02 +1 1686 -1.321900e+03 6.580601e+02 +2 1686 -4.665900e+02 3.324700e+02 +5 1686 2.874700e+02 8.210800e+02 +6 1686 -8.011100e+02 4.479600e+02 +7 1686 1.237500e+02 4.778000e+02 +9 1686 -4.649399e+02 3.868301e+02 +10 1686 -3.461500e+02 -2.615000e+02 +11 1686 1.933600e+02 3.162500e+02 +16 1686 3.303900e+02 4.493600e+02 +1 1687 -8.703200e+02 6.810500e+02 +2 1687 -2.726600e+02 3.802000e+02 +10 1687 -2.339200e+02 -2.337000e+02 +18 1687 -4.649900e+02 1.523500e+02 +20 1687 -3.936000e+02 -6.678003e+01 +1 1688 -1.170290e+03 7.552600e+02 +4 1688 8.183701e+02 4.566200e+02 +5 1688 3.298500e+02 8.680500e+02 +7 1688 1.677400e+02 5.147600e+02 +8 1688 -9.225100e+02 6.568000e+02 +9 1688 -4.096801e+02 4.336799e+02 +10 1688 -3.064800e+02 -2.291500e+02 +12 1688 -9.353100e+02 -3.252100e+02 +18 1688 -5.276700e+02 1.546500e+02 +20 1688 -4.473400e+02 -6.520996e+01 +1 1689 -1.168710e+03 8.501899e+02 +4 1689 8.187100e+02 4.815300e+02 +5 1689 3.250900e+02 9.014600e+02 +7 1689 1.677200e+02 5.463500e+02 +8 1689 -9.208600e+02 7.290699e+02 +10 1689 -3.069800e+02 -2.007600e+02 +12 1689 -9.345900e+02 -2.939200e+02 +18 1689 -5.276000e+02 1.798101e+02 +20 1689 -4.472700e+02 -4.372998e+01 +1 1690 -5.535900e+02 -5.160100e+02 +6 1690 -2.340600e+02 -3.784900e+02 +1 1691 7.798799e+02 -4.577700e+02 +3 1691 7.845100e+02 -3.608000e+02 +6 1691 7.094301e+02 -3.777800e+02 +1 1692 -8.173500e+02 -4.504000e+02 +6 1692 -4.562700e+02 -3.218700e+02 +1 1693 -8.599100e+02 -4.259399e+02 +3 1693 -8.339500e+02 -3.412900e+02 +6 1693 -4.916100e+02 -3.038000e+02 +1 1694 -8.599100e+02 -4.259399e+02 +3 1694 -8.339500e+02 -3.412900e+02 +1 1695 -8.775100e+02 -4.138400e+02 +3 1695 -8.491300e+02 -3.277000e+02 +1 1696 -9.749800e+02 -4.088199e+02 +6 1696 -5.810000e+02 -2.876900e+02 +1 1697 -9.749800e+02 -4.088199e+02 +6 1697 -5.810000e+02 -2.876900e+02 +1 1698 -1.136530e+03 -4.094800e+02 +6 1698 -7.044500e+02 -2.805900e+02 +1 1699 1.194301e+02 -3.904100e+02 +3 1699 5.904200e+02 -2.790400e+02 +6 1699 -6.069000e+01 -2.854700e+02 +1 1700 7.797700e+02 -3.868500e+02 +3 1700 7.850000e+02 -2.899600e+02 +1 1701 8.480701e+02 -3.855300e+02 +2 1701 6.741600e+02 -2.102000e+02 +1 1702 -3.579700e+02 -3.824800e+02 +3 1702 -4.304700e+02 -2.951801e+02 +1 1703 1.147280e+03 -3.753300e+02 +6 1703 9.590900e+02 -3.264500e+02 +1 1704 -3.403300e+02 -3.504500e+02 +3 1704 -4.172400e+02 -2.664800e+02 +1 1705 -1.040840e+03 -3.372300e+02 +2 1705 -3.198000e+02 -2.010100e+02 +9 1705 -3.476400e+02 -1.544995e+01 +10 1705 -2.641500e+02 -5.506899e+02 +11 1705 3.031400e+02 -6.910999e+01 +20 1705 -4.198400e+02 -3.075300e+02 +1 1706 -1.238330e+03 -3.336000e+02 +2 1706 -4.078200e+02 -2.030600e+02 +7 1706 1.583700e+02 1.596300e+02 +9 1706 -4.152800e+02 -1.851001e+01 +10 1706 -3.152300e+02 -5.517900e+02 +11 1706 2.394200e+02 -7.182001e+01 +1 1707 -1.551001e+01 -2.973300e+02 +6 1707 3.347000e+02 -2.590100e+02 +8 1707 6.334800e+02 -9.567999e+01 +1 1708 -1.038090e+03 -2.947300e+02 +6 1708 -6.288200e+02 -2.060800e+02 +1 1709 -1.152920e+03 -2.882500e+02 +2 1709 -3.691100e+02 -1.777100e+02 +6 1709 -7.131600e+02 -1.981800e+02 +7 1709 1.822800e+02 1.746300e+02 +9 1709 -3.855699e+02 1.439941e+00 +11 1709 2.671300e+02 -5.300000e+01 +12 1709 -9.310100e+02 -6.681700e+02 +18 1709 -5.189500e+02 -1.150601e+02 +20 1709 -4.405400e+02 -2.981801e+02 +1 1710 1.097060e+03 -2.670800e+02 +5 1710 1.240670e+03 6.561600e+02 +6 1710 9.224000e+02 -2.438200e+02 +7 1710 9.389299e+02 1.883500e+02 +8 1710 9.063500e+02 -1.029900e+02 +12 1710 -1.901500e+02 -6.511700e+02 +16 1710 9.937700e+02 2.389200e+02 +17 1710 -8.666800e+02 1.045300e+02 +1 1711 8.671299e+02 -2.610000e+02 +2 1711 6.855300e+02 -1.386400e+02 +3 1711 9.130601e+02 -1.589700e+02 +1 1712 -3.578900e+02 -2.376000e+02 +3 1712 -4.325500e+02 -1.473000e+02 +11 1712 4.719301e+02 2.256000e+01 +1 1713 -1.386100e+02 -2.259200e+02 +6 1713 1.583700e+02 -1.968000e+02 +1 1714 -1.386100e+02 -2.259200e+02 +6 1714 1.583700e+02 -1.968000e+02 +1 1715 -4.470800e+02 -1.926000e+02 +4 1715 1.070190e+03 2.368500e+02 +5 1715 7.049700e+02 6.168101e+02 +6 1715 -1.320000e+02 -1.594300e+02 +1 1716 7.749900e+02 -1.894100e+02 +2 1716 6.284100e+02 -8.875000e+01 +3 1716 7.797600e+02 -9.202002e+01 +6 1716 7.123600e+02 -1.837400e+02 +1 1717 -8.513600e+02 -1.485000e+02 +5 1717 4.972700e+02 5.868400e+02 +1 1718 7.885200e+02 -1.292400e+02 +2 1718 6.373000e+02 -5.390002e+01 +1 1719 -4.106006e+01 -1.285500e+02 +6 1719 3.213800e+02 -1.438700e+02 +1 1720 7.095801e+02 -1.243000e+02 +2 1720 5.881400e+02 -4.609003e+01 +3 1720 7.051700e+02 -2.519000e+01 +17 1720 -1.229940e+03 2.613700e+02 +1 1721 -1.639900e+02 -1.250400e+02 +3 1721 -3.158000e+02 -4.132001e+01 +1 1722 -3.564500e+02 -1.098600e+02 +2 1722 -1.139800e+02 -1.576001e+01 +3 1722 -4.326100e+02 -1.794000e+01 +11 1722 4.713400e+02 8.726001e+01 +13 1722 -1.211250e+03 2.105200e+02 +18 1722 -3.695699e+02 -2.717004e+01 +20 1722 -3.123900e+02 -2.215100e+02 +1 1723 1.260050e+03 -9.937000e+01 +7 1723 9.994600e+02 2.463900e+02 +1 1724 -6.301500e+02 -9.385999e+01 +2 1724 -1.912300e+02 -4.059998e+01 +3 1724 -6.448800e+02 6.580017e+00 +7 1724 3.290500e+02 2.567500e+02 +9 1724 -2.375100e+02 1.162400e+02 +11 1724 4.039800e+02 5.709003e+01 +13 1724 -1.489020e+03 1.638401e+02 +18 1724 -4.210100e+02 -4.519995e+01 +20 1724 -3.564200e+02 -2.368000e+02 +1 1725 8.281101e+02 -6.973999e+01 +2 1725 6.626500e+02 -2.817999e+01 +1 1726 8.281101e+02 -6.973999e+01 +2 1726 6.626500e+02 -2.817999e+01 +17 1726 -1.103560e+03 2.836100e+02 +1 1727 7.719900e+02 -6.653003e+01 +2 1727 6.272800e+02 -1.512000e+01 +3 1727 7.770400e+02 3.257001e+01 +12 1727 -2.791500e+02 -5.657500e+02 +17 1727 -1.166020e+03 3.070300e+02 +1 1728 9.318501e+02 -5.285999e+01 +2 1728 7.236400e+02 -2.367999e+01 +1 1729 -5.579400e+02 -5.302002e+01 +2 1729 -1.697100e+02 -1.052002e+01 +3 1729 -5.851400e+02 4.660999e+01 +11 1729 4.216700e+02 8.090997e+01 +18 1729 -4.075699e+02 -2.973999e+01 +20 1729 -3.451200e+02 -2.236300e+02 +1 1730 -7.412500e+02 -1.277002e+01 +2 1730 -2.247800e+02 -4.750000e+00 +7 1730 2.956400e+02 2.788900e+02 +9 1730 -2.678600e+02 1.402300e+02 +10 1730 -2.018500e+02 -4.423000e+02 +11 1730 3.764301e+02 8.040997e+01 +13 1730 -1.597110e+03 2.583600e+02 +18 1730 -4.408800e+02 -2.965002e+01 +20 1730 -3.734600e+02 -2.232000e+02 +1 1731 1.396900e+03 -3.650024e+00 +7 1731 1.048930e+03 2.803401e+02 +9 1731 6.642700e+02 1.483800e+02 +10 1731 4.604800e+02 -4.337500e+02 +12 1731 -9.073999e+01 -5.646700e+02 +13 1731 1.403180e+03 2.154600e+02 +17 1731 -6.196000e+02 3.178401e+02 +18 1731 1.363101e+02 -3.731995e+01 +1 1732 -6.952400e+02 2.209998e+01 +7 1732 3.087500e+02 2.949600e+02 +1 1733 -3.490000e+02 4.823999e+01 +3 1733 -4.276500e+02 1.452400e+02 +1 1734 7.691101e+02 6.797998e+01 +2 1734 6.261899e+02 6.577002e+01 +3 1734 7.737300e+02 1.694100e+02 +6 1734 7.132200e+02 4.179993e+00 +7 1734 8.498000e+02 3.246599e+02 +17 1734 -1.167480e+03 4.309600e+02 +1 1735 1.007560e+03 1.046200e+02 +2 1735 7.676600e+02 6.310999e+01 +3 1735 1.070150e+03 2.113401e+02 +7 1735 9.132600e+02 3.234600e+02 +8 1735 8.431400e+02 2.104700e+02 +12 1735 -2.150900e+02 -5.227400e+02 +17 1735 -9.356200e+02 4.214000e+02 +1 1736 1.007560e+03 1.046200e+02 +2 1736 7.676600e+02 6.310999e+01 +3 1736 1.070150e+03 2.113401e+02 +8 1736 8.431400e+02 2.104700e+02 +1 1737 -8.154400e+02 1.168500e+02 +6 1737 -4.406100e+02 6.887000e+01 +9 1737 -2.936000e+02 1.914900e+02 +12 1737 -8.428200e+02 -5.180000e+02 +13 1737 -1.683000e+03 4.334299e+02 +18 1737 -4.566801e+02 2.280029e+00 +1 1738 1.400290e+03 1.343600e+02 +7 1738 1.050580e+03 3.308500e+02 +9 1738 6.649700e+02 2.083101e+02 +10 1738 4.597700e+02 -3.902100e+02 +12 1738 -8.928003e+01 -5.170601e+02 +13 1738 1.412710e+03 4.080801e+02 +17 1738 -6.138500e+02 4.322400e+02 +18 1738 1.383101e+02 -4.300537e-01 +20 1738 1.251500e+02 -1.948300e+02 +1 1739 -1.315890e+03 1.382400e+02 +6 1739 -8.085200e+02 9.459998e+01 +1 1740 -1.315890e+03 1.382400e+02 +6 1740 -8.085200e+02 9.459998e+01 +1 1741 -4.546100e+02 1.392500e+02 +3 1741 -5.096100e+02 2.428301e+02 +7 1741 3.851600e+02 3.601300e+02 +11 1741 4.445900e+02 1.902800e+02 +13 1741 -1.313570e+03 5.749600e+02 +1 1742 -6.105100e+02 1.479299e+02 +3 1742 -6.347300e+02 2.591699e+02 +1 1743 -8.218100e+02 1.606000e+02 +2 1743 -2.545300e+02 8.896997e+01 +6 1743 -4.407300e+02 9.734003e+01 +7 1743 2.711899e+02 3.346100e+02 +9 1743 -2.937200e+02 2.101400e+02 +10 1743 -2.217600e+02 -3.918700e+02 +11 1743 3.530500e+02 1.477400e+02 +12 1743 -8.419900e+02 -5.034500e+02 +13 1743 -1.681130e+03 4.930500e+02 +18 1743 -4.566500e+02 1.370996e+01 +20 1743 -3.870000e+02 -1.866400e+02 +1 1744 -1.160380e+03 1.781599e+02 +2 1744 -3.808900e+02 7.409998e+01 +4 1744 8.239700e+02 3.079500e+02 +5 1744 3.665800e+02 6.717100e+02 +6 1744 -7.037800e+02 1.215300e+02 +9 1744 -3.961801e+02 1.916699e+02 +11 1744 2.575400e+02 1.299800e+02 +12 1744 -9.319800e+02 -5.158101e+02 +1 1745 8.605701e+02 1.868401e+02 +2 1745 6.852500e+02 1.169900e+02 +17 1745 -1.065090e+03 5.066500e+02 +1 1746 8.401699e+02 1.903700e+02 +2 1746 6.723800e+02 1.228300e+02 +3 1746 8.792700e+02 2.998900e+02 +6 1746 7.503800e+02 9.556000e+01 +17 1746 -1.084950e+03 5.165801e+02 +1 1747 1.306480e+03 2.336799e+02 +7 1747 1.021740e+03 3.671100e+02 +12 1747 -1.161000e+02 -4.832100e+02 +20 1747 1.056700e+02 -1.712500e+02 +1 1748 1.398310e+03 2.394900e+02 +7 1748 1.052280e+03 3.680901e+02 +9 1748 6.658899e+02 2.529600e+02 +10 1748 4.601101e+02 -3.576801e+02 +12 1748 -8.889001e+01 -4.831400e+02 +13 1748 1.414910e+03 5.526699e+02 +17 1748 -6.138600e+02 5.199299e+02 +20 1748 1.260400e+02 -1.702800e+02 +1 1749 -1.147990e+03 2.402800e+02 +2 1749 -3.768000e+02 1.096100e+02 +9 1749 -3.943800e+02 2.181699e+02 +10 1749 -2.963800e+02 -3.816500e+02 +11 1749 2.599700e+02 1.557400e+02 +12 1749 -9.287100e+02 -4.946600e+02 +18 1749 -5.204100e+02 2.089001e+01 +20 1749 -4.419700e+02 -1.805900e+02 +1 1750 7.631101e+02 2.524099e+02 +2 1750 6.232400e+02 1.771900e+02 +3 1750 7.655800e+02 3.573900e+02 +6 1750 7.110000e+02 1.379900e+02 +7 1750 8.498401e+02 3.961200e+02 +1 1751 -5.021100e+02 2.540200e+02 +2 1751 -1.524300e+02 1.874900e+02 +3 1751 -5.420000e+02 3.671400e+02 +7 1751 3.689399e+02 3.970200e+02 +9 1751 -2.028101e+02 2.988500e+02 +10 1751 -1.498600e+02 -3.361000e+02 +11 1751 4.358600e+02 2.337700e+02 +12 1751 -7.525000e+02 -4.347600e+02 +13 1751 -1.353020e+03 7.296200e+02 +18 1751 -3.958600e+02 6.814001e+01 +20 1751 -3.348400e+02 -1.395900e+02 +1 1752 1.285500e+03 2.619700e+02 +7 1752 1.014510e+03 3.796500e+02 +13 1752 1.267870e+03 5.972000e+02 +17 1752 -7.052700e+02 5.470901e+02 +20 1752 1.013800e+02 -1.632700e+02 +1 1753 8.246599e+02 2.942400e+02 +2 1753 6.648000e+02 1.876000e+02 +17 1753 -1.101320e+03 6.142300e+02 +1 1754 -4.156300e+02 2.955000e+02 +3 1754 -4.787300e+02 4.048201e+02 +1 1755 -7.173000e+02 3.330400e+02 +6 1755 -3.499900e+02 2.122700e+02 +1 1756 1.356460e+03 3.621699e+02 +7 1756 1.042490e+03 4.145100e+02 +17 1756 -6.438700e+02 6.266100e+02 +1 1757 -4.313900e+02 3.846000e+02 +2 1757 -1.408000e+02 2.929200e+02 +10 1757 -1.368800e+02 -2.777000e+02 +13 1757 -1.291390e+03 9.898701e+02 +1 1758 8.607800e+02 3.990801e+02 +6 1758 7.687900e+02 2.488700e+02 +7 1758 8.714700e+02 4.379399e+02 +1 1759 -1.277210e+03 4.354199e+02 +7 1759 1.392000e+02 4.055601e+02 +12 1759 -9.681300e+02 -4.336700e+02 +1 1760 -1.321720e+03 4.447300e+02 +2 1760 -4.632800e+02 2.154900e+02 +4 1760 7.826699e+02 3.721599e+02 +5 1760 3.009100e+02 7.493300e+02 +9 1760 -4.605400e+02 2.972900e+02 +10 1760 -3.441700e+02 -3.241100e+02 +11 1760 1.964800e+02 2.308500e+02 +12 1760 -9.820500e+02 -4.310100e+02 +16 1760 3.329900e+02 3.965400e+02 +18 1760 -5.615900e+02 7.075000e+01 +1 1761 -1.453650e+03 4.684700e+02 +2 1761 -5.275300e+02 2.247200e+02 +7 1761 8.706006e+01 4.126100e+02 +9 1761 -5.112200e+02 3.035200e+02 +11 1761 1.496899e+02 2.363600e+02 +1 1762 9.116599e+02 4.987200e+02 +2 1762 7.129399e+02 4.174800e+02 +7 1762 9.794099e+02 5.573600e+02 +12 1762 -1.679399e+02 -2.830300e+02 +17 1762 -1.075380e+03 9.692000e+02 +18 1762 5.422998e+01 1.876699e+02 +1 1763 9.116599e+02 4.987200e+02 +2 1763 7.129399e+02 4.174800e+02 +3 1763 8.026200e+02 5.848101e+02 +7 1763 9.794099e+02 5.573600e+02 +1 1764 8.892500e+02 5.025200e+02 +2 1764 6.912600e+02 4.172500e+02 +3 1764 7.818500e+02 5.897200e+02 +17 1764 -1.104600e+03 9.712300e+02 +18 1764 4.406995e+01 1.873101e+02 +1 1765 7.809800e+02 5.556200e+02 +6 1765 7.930300e+02 3.423300e+02 +8 1765 9.552600e+02 6.580300e+02 +1 1766 -1.160280e+03 6.330800e+02 +2 1766 -3.893500e+02 3.249300e+02 +4 1766 8.220901e+02 4.252600e+02 +5 1766 3.411000e+02 8.269800e+02 +6 1766 -6.898100e+02 4.295100e+02 +7 1766 1.716801e+02 4.744399e+02 +8 1766 -9.131200e+02 5.658400e+02 +9 1766 -4.053800e+02 3.827000e+02 +10 1766 -3.033800e+02 -2.648600e+02 +11 1766 2.501100e+02 3.133500e+02 +12 1766 -9.330800e+02 -3.649600e+02 +18 1766 -5.252900e+02 1.231699e+02 +20 1766 -4.452100e+02 -9.244995e+01 +1 1767 -1.252920e+03 6.668600e+02 +2 1767 -4.344300e+02 3.390900e+02 +7 1767 1.428500e+02 4.820601e+02 +9 1767 -4.401600e+02 3.920300e+02 +11 1767 2.170000e+02 3.221100e+02 +1 1768 -1.369990e+03 6.696500e+02 +2 1768 -4.895800e+02 3.371400e+02 +7 1768 1.095699e+02 4.799399e+02 +11 1768 1.767400e+02 3.180700e+02 +16 1768 3.190200e+02 4.513700e+02 +18 1768 -5.734800e+02 1.281000e+02 +1 1769 -1.448720e+03 6.698201e+02 +5 1769 2.481400e+02 8.153500e+02 +1 1770 -8.335100e+02 6.738400e+02 +4 1770 9.171299e+02 4.601500e+02 +5 1770 4.600601e+02 8.873900e+02 +8 1770 -6.308800e+02 6.259700e+02 +1 1771 -1.317910e+03 7.974800e+02 +2 1771 -4.665100e+02 4.096500e+02 +4 1771 7.809900e+02 4.622100e+02 +9 1771 -4.660300e+02 4.447700e+02 +11 1771 1.931700e+02 3.726899e+02 +1 1772 -1.342800e+03 7.972300e+02 +2 1772 -4.792300e+02 4.083700e+02 +4 1772 7.746799e+02 4.612100e+02 +5 1772 2.722200e+02 8.663700e+02 +9 1772 -4.755100e+02 4.435400e+02 +11 1772 1.838700e+02 3.716200e+02 +12 1772 -9.886500e+02 -3.159900e+02 +18 1772 -5.683700e+02 1.619600e+02 +1 1773 -1.302070e+03 8.156200e+02 +4 1773 7.847600e+02 4.669900e+02 +1 1774 -1.149150e+03 8.623800e+02 +2 1774 -3.886500e+02 4.532100e+02 +4 1774 8.238799e+02 4.858800e+02 +10 1774 -3.021899e+02 -1.962000e+02 +11 1774 2.502200e+02 4.082700e+02 +12 1774 -9.289000e+02 -2.894399e+02 +18 1774 -5.233900e+02 1.840500e+02 +20 1774 -4.441500e+02 -4.031006e+01 +1 1775 -1.276630e+03 8.985400e+02 +2 1775 -4.488800e+02 4.671100e+02 +11 1775 2.059000e+02 4.157300e+02 +18 1775 -5.529500e+02 1.899299e+02 +20 1775 -4.693400e+02 -3.506995e+01 +1 1776 -1.070240e+03 -5.689399e+02 +3 1776 -1.027940e+03 -4.944000e+02 +1 1777 7.820701e+02 -5.137200e+02 +3 1777 7.868700e+02 -4.175000e+02 +6 1777 7.099800e+02 -4.176700e+02 +1 1778 -8.215600e+02 -4.344600e+02 +3 1778 -8.020600e+02 -3.505000e+02 +1 1779 -8.335300e+02 -4.254399e+02 +3 1779 -8.137600e+02 -3.410400e+02 +6 1779 -4.682300e+02 -3.044000e+02 +10 1779 -2.200000e+02 -5.735500e+02 +12 1779 -8.471600e+02 -7.058199e+02 +18 1779 -4.577400e+02 -1.446300e+02 +20 1779 -3.879301e+02 -3.233101e+02 +1 1780 -9.850500e+02 -4.239000e+02 +6 1780 -5.904300e+02 -2.981600e+02 +10 1780 -2.530601e+02 -5.757500e+02 +1 1781 -4.304200e+02 -4.200601e+02 +6 1781 -1.257000e+02 -3.167100e+02 +1 1782 -4.512800e+02 -4.152000e+02 +6 1782 -1.409000e+02 -3.136100e+02 +1 1783 -7.980100e+02 -4.140500e+02 +6 1783 -4.398700e+02 -2.979100e+02 +1 1784 -1.300300e+02 -3.929600e+02 +3 1784 -2.867900e+02 -3.070300e+02 +1 1785 9.267500e+02 -3.786400e+02 +2 1785 7.198300e+02 -2.078900e+02 +1 1786 8.930601e+02 -3.799900e+02 +2 1786 7.004900e+02 -2.070800e+02 +3 1786 9.422700e+02 -2.801700e+02 +1 1787 1.047930e+03 -3.761200e+02 +8 1787 8.649301e+02 -1.932700e+02 +1 1788 9.717900e+02 -3.765699e+02 +3 1788 1.029310e+03 -2.771300e+02 +1 1789 1.078490e+03 -3.755500e+02 +6 1789 9.066500e+02 -3.249500e+02 +1 1790 -5.126800e+02 -3.747200e+02 +6 1790 -1.936200e+02 -2.828300e+02 +1 1791 7.793999e+02 -3.681400e+02 +2 1791 6.303000e+02 -1.945200e+02 +3 1791 7.845699e+02 -2.713800e+02 +1 1792 -4.340100e+02 -3.667500e+02 +5 1792 7.185800e+02 5.468000e+02 +6 1792 -1.264400e+02 -2.808800e+02 +1 1793 -1.073000e+03 -3.660699e+02 +2 1793 -3.333800e+02 -2.173100e+02 +9 1793 -3.574000e+02 -2.781006e+01 +11 1793 2.924000e+02 -8.137000e+01 +1 1794 1.036400e+03 -3.647300e+02 +8 1794 8.556899e+02 -1.837700e+02 +1 1795 9.970300e+02 -3.655500e+02 +2 1795 7.584500e+02 -2.005700e+02 +3 1795 1.058170e+03 -2.645200e+02 +1 1796 9.970300e+02 -3.655500e+02 +2 1796 7.584500e+02 -2.005700e+02 +1 1797 7.678701e+02 -3.549100e+02 +2 1797 6.234301e+02 -1.863000e+02 +3 1797 7.725900e+02 -2.572800e+02 +1 1798 -4.598400e+02 -3.541500e+02 +6 1798 -1.448200e+02 -2.709700e+02 +1 1799 -8.481200e+02 -3.462000e+02 +3 1799 -8.284600e+02 -2.567600e+02 +1 1800 7.783501e+02 -3.416100e+02 +2 1800 6.300500e+02 -1.792800e+02 +3 1800 7.838800e+02 -2.447500e+02 +1 1801 -8.177600e+02 -3.345500e+02 +3 1801 -7.996700e+02 -2.464301e+02 +1 1802 -1.323770e+03 -3.332600e+02 +6 1802 -8.336600e+02 -2.242200e+02 +1 1803 8.926001e+02 -3.283700e+02 +2 1803 6.999301e+02 -1.787200e+02 +1 1804 -1.132640e+03 -3.248500e+02 +7 1804 1.887000e+02 1.632400e+02 +9 1804 -3.783000e+02 -1.375000e+01 +11 1804 2.739700e+02 -6.728003e+01 +12 1804 -9.250200e+02 -6.795200e+02 +18 1804 -5.137500e+02 -1.235800e+02 +1 1805 7.653301e+02 -3.041700e+02 +2 1805 6.218800e+02 -1.561100e+02 +3 1805 7.697200e+02 -2.063101e+02 +6 1805 7.021600e+02 -2.651800e+02 +12 1805 -2.843101e+02 -6.522100e+02 +1 1806 -1.289399e+02 -2.881600e+02 +3 1806 -2.853200e+02 -2.050800e+02 +1 1807 8.718401e+02 -2.852700e+02 +2 1807 6.887700e+02 -1.532700e+02 +3 1807 9.189800e+02 -1.840800e+02 +6 1807 7.599100e+02 -2.520600e+02 +1 1808 -6.719971e+00 -2.837400e+02 +6 1808 3.416500e+02 -2.494500e+02 +1 1809 7.775601e+02 -2.769200e+02 +2 1809 6.295100e+02 -1.398700e+02 +3 1809 7.823900e+02 -1.788500e+02 +1 1810 1.371950e+03 -2.754700e+02 +7 1810 1.034420e+03 1.839000e+02 +9 1810 6.495100e+02 3.212000e+01 +10 1810 4.524900e+02 -5.163700e+02 +1 1811 -1.437900e+02 -2.685200e+02 +3 1811 -2.926900e+02 -1.867800e+02 +11 1811 5.212600e+02 3.839001e+01 +13 1811 -9.876500e+02 1.270020e+00 +18 1811 -3.276200e+02 -5.753003e+01 +20 1811 -2.770800e+02 -2.459301e+02 +1 1812 -1.080650e+03 -2.686801e+02 +2 1812 -3.375200e+02 -1.654500e+02 +3 1812 -1.046090e+03 -1.735400e+02 +4 1812 8.447800e+02 1.964700e+02 +5 1812 4.171500e+02 5.283900e+02 +6 1812 -6.601000e+02 -1.872000e+02 +7 1812 2.030300e+02 1.819099e+02 +9 1812 -3.610800e+02 1.142004e+01 +11 1812 2.902700e+02 -4.385999e+01 +12 1812 -9.100400e+02 -6.603199e+02 +18 1812 -5.029500e+02 -1.092400e+02 +1 1813 8.327300e+02 -2.568101e+02 +2 1813 6.646600e+02 -1.333600e+02 +1 1814 -1.543101e+02 -2.154600e+02 +6 1814 1.459000e+02 -1.903900e+02 +1 1815 -5.602500e+02 -2.041700e+02 +6 1815 -2.330400e+02 -1.649100e+02 +1 1816 9.658701e+02 -1.884900e+02 +2 1816 7.422500e+02 -1.003600e+02 +17 1816 -9.759500e+02 1.751200e+02 +1 1817 -3.961100e+02 -1.831300e+02 +3 1817 -4.601000e+02 -9.053003e+01 +1 1818 6.208101e+02 -1.703199e+02 +2 1818 5.106200e+02 -4.623999e+01 +11 1818 9.796801e+02 7.273999e+01 +17 1818 -1.378880e+03 2.636500e+02 +1 1819 -1.180200e+02 -1.631899e+02 +3 1819 -2.790900e+02 -7.884003e+01 +6 1819 1.787900e+02 -1.576400e+02 +9 1819 -9.285999e+01 1.723500e+02 +10 1819 -5.769995e+01 -4.417300e+02 +11 1819 5.252200e+02 1.098600e+02 +13 1819 -9.575200e+02 2.148401e+02 +20 1819 -2.727200e+02 -2.080100e+02 +1 1820 -2.846997e+01 -1.413800e+02 +6 1820 3.304900e+02 -1.522300e+02 +8 1820 6.251100e+02 5.845001e+01 +16 1820 8.063000e+02 3.621200e+02 +1 1821 -1.386899e+02 -1.031400e+02 +3 1821 -3.010700e+02 -1.991998e+01 +1 1822 7.727700e+02 -9.889001e+01 +2 1822 6.274399e+02 -3.457001e+01 +3 1822 7.776200e+02 -3.300171e-01 +6 1822 7.125300e+02 -1.159800e+02 +12 1822 -2.793700e+02 -5.777300e+02 +17 1822 -1.165540e+03 2.774800e+02 +1 1823 1.313630e+03 -9.775000e+01 +7 1823 1.017210e+03 2.465200e+02 +9 1823 6.271201e+02 1.072300e+02 +10 1823 4.336101e+02 -4.632600e+02 +1 1824 -3.734200e+02 -9.714001e+01 +2 1824 -1.196700e+02 -1.034998e+01 +3 1824 -4.460400e+02 -2.969971e+00 +7 1824 4.144200e+02 2.758401e+02 +11 1824 4.663199e+02 9.053998e+01 +13 1824 -1.230870e+03 2.268500e+02 +18 1824 -3.731600e+02 -2.456006e+01 +1 1825 8.000100e+02 -9.439001e+01 +2 1825 6.448000e+02 -3.528003e+01 +17 1825 -1.135960e+03 2.768700e+02 +1 1826 7.861101e+02 -9.327002e+01 +3 1826 7.946500e+02 8.090027e+00 +1 1827 7.861101e+02 -9.327002e+01 +2 1827 6.359600e+02 -3.110999e+01 +3 1827 7.945400e+02 8.270020e+00 +17 1827 -1.151090e+03 2.824000e+02 +1 1828 -1.524200e+02 -9.195996e+01 +3 1828 -3.111600e+02 -6.320007e+00 +9 1828 -1.119100e+02 2.159700e+02 +18 1828 -3.337200e+02 1.480005e+01 +1 1829 -8.789500e+02 -8.618994e+01 +2 1829 -2.659300e+02 -5.670001e+01 +7 1829 2.578700e+02 2.467800e+02 +12 1829 -8.564600e+02 -5.929000e+02 +18 1829 -4.645900e+02 -5.622998e+01 +1 1830 -6.291000e+02 -7.756006e+01 +2 1830 -1.911800e+02 -3.028003e+01 +7 1830 3.291801e+02 2.629900e+02 +9 1830 -2.370400e+02 1.244000e+02 +11 1830 4.041100e+02 6.503003e+01 +13 1830 -1.488690e+03 1.891400e+02 +18 1830 -4.210100e+02 -4.005005e+01 +1 1831 -1.110890e+03 -5.922998e+01 +2 1831 -3.544700e+02 -5.345001e+01 +7 1831 1.921500e+02 2.483000e+02 +9 1831 -3.750900e+02 9.568005e+01 +11 1831 2.771300e+02 3.747998e+01 +18 1831 -5.103000e+02 -5.605005e+01 +1 1832 -6.343400e+02 5.739990e+00 +7 1832 3.271200e+02 2.932900e+02 +1 1833 -2.520200e+02 1.998999e+01 +3 1833 -3.679400e+02 1.108900e+02 +1 1834 -2.520200e+02 1.998999e+01 +6 1834 5.665002e+01 -2.373999e+01 +1 1835 -2.929000e+02 4.833008e+01 +6 1835 1.795996e+01 -2.190002e+00 +1 1836 -1.367440e+03 5.795996e+01 +2 1836 -4.782400e+02 3.510010e+00 +7 1836 1.160800e+02 2.819500e+02 +10 1836 -3.544200e+02 -4.393101e+02 +11 1836 1.865400e+02 7.638000e+01 +12 1836 -9.974800e+02 -5.585500e+02 +1 1837 9.548101e+02 6.928003e+01 +6 1837 8.270000e+02 5.450012e+00 +7 1837 8.963201e+02 3.126000e+02 +1 1838 9.533701e+02 1.135601e+02 +2 1838 7.385900e+02 7.121997e+01 +3 1838 1.011020e+03 2.208401e+02 +1 1839 9.533701e+02 1.135601e+02 +6 1839 8.251300e+02 3.896997e+01 +1 1840 1.352730e+03 1.180500e+02 +7 1840 1.035870e+03 3.246899e+02 +12 1840 -1.029000e+02 -5.230400e+02 +13 1840 1.351160e+03 3.874199e+02 +17 1840 -6.523800e+02 4.203900e+02 +20 1840 1.154700e+02 -1.980500e+02 +1 1841 1.352730e+03 1.180500e+02 +7 1841 1.035870e+03 3.246899e+02 +12 1841 -1.029000e+02 -5.230400e+02 +13 1841 1.351160e+03 3.874199e+02 +17 1841 -6.523800e+02 4.203900e+02 +18 1841 1.266899e+02 -4.150024e+00 +20 1841 1.154700e+02 -1.980500e+02 +1 1842 -4.336200e+02 1.435300e+02 +2 1842 -1.398000e+02 1.314600e+02 +3 1842 -4.953000e+02 2.484800e+02 +7 1842 3.921300e+02 3.632900e+02 +12 1842 -7.350100e+02 -4.670300e+02 +13 1842 -1.294720e+03 5.853201e+02 +18 1842 -3.856801e+02 4.422998e+01 +20 1842 -3.259301e+02 -1.600100e+02 +1 1843 -3.322300e+02 1.542900e+02 +6 1843 -2.082001e+01 7.312000e+01 +16 1843 6.038101e+02 3.820601e+02 +1 1844 -3.577800e+02 1.708301e+02 +2 1844 -1.167300e+02 1.634000e+02 +9 1844 -1.640000e+02 2.893900e+02 +1 1845 -6.557500e+02 1.809000e+02 +3 1845 -6.749500e+02 2.948201e+02 +7 1845 3.191801e+02 3.564399e+02 +10 1845 -1.875000e+02 -3.722200e+02 +12 1845 -7.996900e+02 -4.774900e+02 +13 1845 -1.527150e+03 5.757600e+02 +1 1846 -1.024520e+03 1.801200e+02 +2 1846 -3.220700e+02 8.101001e+01 +3 1846 -1.003160e+03 3.103700e+02 +4 1846 8.599900e+02 3.122700e+02 +10 1846 -2.656300e+02 -3.964600e+02 +11 1846 3.011899e+02 1.368300e+02 +12 1846 -8.948200e+02 -5.107600e+02 +18 1846 -4.938500e+02 7.869995e+00 +20 1846 -4.186200e+02 -1.915000e+02 +1 1847 -1.024520e+03 1.801200e+02 +2 1847 -3.220700e+02 8.101001e+01 +3 1847 -1.003160e+03 3.103700e+02 +4 1847 8.599900e+02 3.122700e+02 +10 1847 -2.656300e+02 -3.964600e+02 +11 1847 3.011899e+02 1.368300e+02 +18 1847 -4.938500e+02 7.869995e+00 +20 1847 -4.186200e+02 -1.915000e+02 +1 1848 -6.870500e+02 1.880701e+02 +7 1848 3.107000e+02 3.572500e+02 +1 1849 9.070601e+02 1.909700e+02 +2 1849 7.121600e+02 1.166600e+02 +3 1849 9.638999e+02 3.009099e+02 +6 1849 7.937200e+02 9.696997e+01 +17 1849 -1.020260e+03 5.053301e+02 +1 1850 -4.223700e+02 1.994299e+02 +3 1850 -4.880000e+02 3.036300e+02 +9 1850 -1.843800e+02 2.926000e+02 +10 1850 -1.337600e+02 -3.439500e+02 +11 1850 4.510601e+02 2.270100e+02 +13 1850 -1.283800e+03 6.879100e+02 +18 1850 -3.829900e+02 6.330005e+01 +1 1851 -6.110800e+02 2.068201e+02 +5 1851 5.894399e+02 7.500300e+02 +1 1852 -1.335390e+03 2.068900e+02 +2 1852 -4.638100e+02 8.490997e+01 +7 1852 1.238300e+02 3.299600e+02 +9 1852 -4.603700e+02 1.979399e+02 +10 1852 -3.455500e+02 -3.952700e+02 +11 1852 1.965800e+02 1.358400e+02 +18 1852 -5.627500e+02 8.880005e+00 +20 1852 -4.784301e+02 -1.908900e+02 +1 1853 1.020050e+03 2.086400e+02 +3 1853 1.085440e+03 3.187700e+02 +6 1853 8.738700e+02 1.103500e+02 +1 1854 9.871499e+02 2.172400e+02 +3 1854 1.050370e+03 3.279000e+02 +17 1854 -9.513700e+02 5.199900e+02 +1 1855 1.365600e+03 2.208600e+02 +7 1855 1.039830e+03 3.620601e+02 +9 1855 6.515601e+02 2.458500e+02 +10 1855 4.490901e+02 -3.637900e+02 +13 1855 1.369560e+03 5.301699e+02 +17 1855 -6.396801e+02 5.062600e+02 +18 1855 1.302900e+02 2.315002e+01 +20 1855 1.178900e+02 -1.746000e+02 +1 1856 -6.516200e+02 2.204000e+02 +7 1856 3.208500e+02 3.708101e+02 +1 1857 -5.677500e+02 2.268700e+02 +3 1857 -5.967400e+02 3.404900e+02 +9 1857 -2.229100e+02 2.728700e+02 +1 1858 -5.677500e+02 2.268700e+02 +3 1858 -5.967400e+02 3.404900e+02 +1 1859 -6.106500e+02 2.374800e+02 +2 1859 -1.983100e+02 1.641100e+02 +7 1859 3.343400e+02 3.799900e+02 +9 1859 -2.438500e+02 2.747100e+02 +1 1860 7.202500e+02 2.550601e+02 +2 1860 5.985699e+02 1.793600e+02 +3 1860 7.251600e+02 3.608600e+02 +17 1860 -1.211780e+03 6.069099e+02 +1 1861 7.770701e+02 2.689199e+02 +2 1861 6.319700e+02 1.865500e+02 +3 1861 7.811100e+02 3.736000e+02 +17 1861 -1.158670e+03 6.162900e+02 +1 1862 8.332600e+02 2.784399e+02 +2 1862 6.689700e+02 1.753700e+02 +6 1862 7.504399e+02 1.603200e+02 +17 1862 -1.092930e+03 5.966599e+02 +1 1863 -4.531400e+02 2.886699e+02 +6 1863 -1.245600e+02 1.704000e+02 +1 1864 -7.419800e+02 2.894000e+02 +2 1864 -2.295800e+02 1.729200e+02 +6 1864 -3.736700e+02 1.833300e+02 +7 1864 2.941600e+02 3.861899e+02 +10 1864 -2.044800e+02 -3.457100e+02 +12 1864 -8.205200e+02 -4.498600e+02 +13 1864 -1.599610e+03 6.995000e+02 +18 1864 -4.417200e+02 5.620996e+01 +1 1865 -6.246400e+02 2.927000e+02 +2 1865 -1.930800e+02 1.895200e+02 +3 1865 -6.446100e+02 4.152500e+02 +7 1865 3.293700e+02 3.961599e+02 +9 1865 -2.400699e+02 2.930100e+02 +10 1865 -1.785500e+02 -3.362300e+02 +11 1865 4.022600e+02 2.280700e+02 +13 1865 -1.483520e+03 7.368101e+02 +18 1865 -4.201200e+02 6.537000e+01 +1 1866 -5.835900e+02 3.024099e+02 +2 1866 -1.803000e+02 2.046000e+02 +3 1866 -6.114200e+02 4.207100e+02 +7 1866 3.425000e+02 4.066899e+02 +9 1866 -2.281200e+02 3.085100e+02 +10 1866 -1.692000e+02 -3.272900e+02 +11 1866 4.123700e+02 2.438000e+02 +12 1866 -7.758500e+02 -4.265100e+02 +13 1866 -1.441120e+03 7.733900e+02 +20 1866 -3.488000e+02 -1.339399e+02 +1 1867 8.472800e+02 3.264500e+02 +2 1867 6.787300e+02 2.005700e+02 +3 1867 8.910000e+02 4.379000e+02 +1 1868 1.377720e+03 3.789199e+02 +7 1868 1.050030e+03 4.204299e+02 +10 1868 4.544500e+02 -3.146500e+02 +12 1868 -9.133997e+01 -4.352500e+02 +13 1868 1.400020e+03 7.506300e+02 +18 1868 1.363600e+02 6.550000e+01 +1 1869 -1.182230e+03 4.291000e+02 +2 1869 -3.978600e+02 2.127800e+02 +7 1869 1.669500e+02 4.055801e+02 +9 1869 -4.101200e+02 2.951000e+02 +11 1869 2.442700e+02 2.298600e+02 +18 1869 -5.298200e+02 6.955005e+01 +1 1870 -8.043100e+02 6.037400e+02 +3 1870 -8.037600e+02 7.575300e+02 +1 1871 -8.043100e+02 6.037400e+02 +3 1871 -8.037600e+02 7.575300e+02 +1 1872 -1.303030e+03 6.486500e+02 +2 1872 -4.580300e+02 3.266300e+02 +7 1872 1.292500e+02 4.746200e+02 +9 1872 -4.583700e+02 3.825400e+02 +11 1872 2.000300e+02 3.126200e+02 +12 1872 -9.758800e+02 -3.642200e+02 +16 1872 3.347300e+02 4.474600e+02 +1 1873 -1.147910e+03 6.573000e+02 +5 1873 3.433600e+02 8.370200e+02 +7 1873 1.744600e+02 4.829299e+02 +9 1873 -4.022800e+02 3.933600e+02 +1 1874 -1.302720e+03 6.759299e+02 +2 1874 -4.580700e+02 3.427400e+02 +6 1874 -7.879400e+02 4.603400e+02 +7 1874 1.289301e+02 4.838600e+02 +9 1874 -4.589900e+02 3.942500e+02 +11 1874 1.995400e+02 3.241000e+02 +12 1874 -9.759800e+02 -3.549900e+02 +1 1875 -1.302720e+03 6.759299e+02 +2 1875 -4.580700e+02 3.427400e+02 +6 1875 -7.879400e+02 4.603400e+02 +7 1875 1.289301e+02 4.838600e+02 +9 1875 -4.589900e+02 3.942500e+02 +10 1875 -3.412600e+02 -2.558900e+02 +11 1875 1.995400e+02 3.241000e+02 +12 1875 -9.759800e+02 -3.549900e+02 +1 1876 -1.345130e+03 7.100200e+02 +5 1876 2.770300e+02 8.362600e+02 +1 1877 -1.450320e+03 8.148000e+02 +2 1877 -5.358700e+02 4.170400e+02 +7 1877 8.256995e+01 5.266699e+02 +9 1877 -5.184300e+02 4.492200e+02 +10 1877 -3.833600e+02 -2.167700e+02 +11 1877 1.427900e+02 3.764200e+02 +16 1877 2.978500e+02 4.861100e+02 +18 1877 -5.949800e+02 1.660601e+02 +1 1878 -1.221840e+03 9.251600e+02 +2 1878 -4.213800e+02 4.833300e+02 +7 1878 1.509900e+02 5.687500e+02 +9 1878 -4.317500e+02 5.022900e+02 +10 1878 -3.213400e+02 -1.805100e+02 +11 1878 2.257300e+02 4.285000e+02 +12 1878 -9.498600e+02 -2.714200e+02 +18 1878 -5.396600e+02 1.976000e+02 +1 1879 -1.208900e+03 9.816000e+02 +6 1879 -7.142200e+02 6.677100e+02 +1 1880 -1.208900e+03 9.816000e+02 +6 1880 -7.142200e+02 6.677100e+02 +1 1881 -1.226430e+03 -5.887000e+02 +6 1881 -7.720900e+02 -4.022700e+02 +1 1882 1.533500e+02 -5.401100e+02 +3 1882 6.243300e+02 -4.437400e+02 +6 1882 -4.148999e+01 -3.995400e+02 +1 1883 -5.356200e+02 -5.411300e+02 +6 1883 -2.182900e+02 -3.969700e+02 +1 1884 9.422998e+01 -5.222300e+02 +3 1884 5.611100e+02 -4.250900e+02 +6 1884 -8.589001e+01 -3.838300e+02 +1 1885 7.717400e+02 -4.862800e+02 +3 1885 7.757200e+02 -3.898900e+02 +6 1885 7.026801e+02 -3.986500e+02 +1 1886 7.900400e+02 -4.689700e+02 +3 1886 7.964100e+02 -3.718300e+02 +1 1887 7.358601e+02 -4.698101e+02 +6 1887 6.774399e+02 -3.853400e+02 +1 1888 -1.039870e+03 -4.528199e+02 +6 1888 -6.332900e+02 -3.146900e+02 +1 1889 7.913701e+02 -4.499100e+02 +3 1889 7.988300e+02 -3.530500e+02 +1 1890 7.691899e+02 -4.491400e+02 +3 1890 7.721700e+02 -3.526700e+02 +6 1890 7.009100e+02 -3.715601e+02 +1 1891 7.896101e+02 -4.332100e+02 +3 1891 7.959700e+02 -3.358800e+02 +1 1892 7.704900e+02 -4.334900e+02 +3 1892 7.745200e+02 -3.363800e+02 +6 1892 7.033700e+02 -3.599900e+02 +1 1893 -5.129300e+02 -4.324500e+02 +6 1893 -1.950800e+02 -3.222600e+02 +1 1894 -1.025200e+03 -4.338300e+02 +6 1894 -6.210200e+02 -3.023300e+02 +1 1895 -1.025200e+03 -4.338300e+02 +6 1895 -6.210200e+02 -3.023300e+02 +1 1896 8.622000e+02 -4.311801e+02 +2 1896 6.833300e+02 -2.355500e+02 +1 1897 -9.661600e+02 -4.260200e+02 +6 1897 -5.761300e+02 -2.993600e+02 +1 1898 -9.661600e+02 -4.260200e+02 +6 1898 -5.761300e+02 -2.993600e+02 +1 1899 7.799800e+02 -4.250900e+02 +3 1899 7.849301e+02 -3.270500e+02 +6 1899 7.103900e+02 -3.542100e+02 +1 1900 -4.426600e+02 -4.255900e+02 +6 1900 -1.348200e+02 -3.213700e+02 +1 1901 -3.393101e+02 -4.196899e+02 +3 1901 -4.167900e+02 -3.344000e+02 +1 1902 -3.723800e+02 -4.186200e+02 +3 1902 -4.407900e+02 -3.328800e+02 +1 1903 7.907500e+02 -4.149301e+02 +3 1903 7.977400e+02 -3.167600e+02 +1 1904 7.695400e+02 -4.148000e+02 +3 1904 7.736600e+02 -3.179500e+02 +6 1904 7.026500e+02 -3.465000e+02 +1 1905 7.798899e+02 -4.059700e+02 +3 1905 7.848500e+02 -3.089900e+02 +1 1906 -3.395800e+02 -4.029500e+02 +3 1906 -4.172100e+02 -3.170900e+02 +1 1907 -8.687900e+02 -4.004301e+02 +3 1907 -8.418400e+02 -3.134500e+02 +6 1907 -5.005600e+02 -2.855200e+02 +1 1908 7.350400e+02 -3.980300e+02 +2 1908 6.047300e+02 -2.119600e+02 +3 1908 7.410200e+02 -3.015200e+02 +6 1908 6.772200e+02 -3.330800e+02 +1 1909 7.916399e+02 -3.965500e+02 +3 1909 7.986000e+02 -2.991801e+02 +1 1910 7.703301e+02 -3.970000e+02 +3 1910 7.743101e+02 -2.999800e+02 +6 1910 7.039399e+02 -3.331700e+02 +17 1910 -1.171110e+03 8.020020e+00 +1 1911 -5.132000e+02 -3.942300e+02 +6 1911 -1.941100e+02 -2.965300e+02 +1 1912 8.608999e+02 -3.923500e+02 +2 1912 6.825200e+02 -2.136700e+02 +1 1913 8.850601e+02 -3.918400e+02 +3 1913 9.334099e+02 -2.925900e+02 +1 1914 1.111000e+02 -3.905699e+02 +6 1914 -6.863000e+01 -2.852400e+02 +1 1915 -4.317000e+02 -3.899900e+02 +6 1915 -1.256500e+02 -2.966000e+02 +1 1916 -4.317000e+02 -3.899900e+02 +6 1916 -1.256500e+02 -2.966000e+02 +1 1917 7.293000e+02 -3.874900e+02 +2 1917 6.010500e+02 -2.055500e+02 +1 1918 7.293000e+02 -3.874900e+02 +2 1918 6.010500e+02 -2.055500e+02 +1 1919 -3.401000e+02 -3.867300e+02 +3 1919 -4.173700e+02 -3.004301e+02 +1 1920 -3.401000e+02 -3.867300e+02 +3 1920 -4.173700e+02 -3.004301e+02 +1 1921 -4.437200e+02 -3.812200e+02 +6 1921 -1.338500e+02 -2.904700e+02 +1 1922 -4.437200e+02 -3.812200e+02 +6 1922 -1.338500e+02 -2.904700e+02 +1 1923 -4.700400e+02 -3.791600e+02 +6 1923 -1.539700e+02 -2.876300e+02 +1 1924 7.673401e+02 -3.754900e+02 +2 1924 6.217600e+02 -1.984400e+02 +1 1925 -3.465300e+02 -3.707200e+02 +3 1925 -4.221700e+02 -2.845100e+02 +1 1926 -5.572500e+02 -3.719301e+02 +6 1926 -2.347700e+02 -2.782500e+02 +1 1927 8.620100e+02 -3.689399e+02 +2 1927 6.826899e+02 -2.002600e+02 +3 1927 9.065400e+02 -2.691100e+02 +1 1928 -3.666801e+02 -3.690800e+02 +3 1928 -4.383800e+02 -2.822500e+02 +1 1929 8.856001e+02 -3.679500e+02 +2 1929 6.950100e+02 -2.003400e+02 +3 1929 9.345200e+02 -2.680900e+02 +1 1930 -8.734400e+02 -3.533400e+02 +3 1930 -8.486200e+02 -2.631700e+02 +1 1931 1.454070e+03 -3.484800e+02 +7 1931 1.061470e+03 1.574199e+02 +18 1931 1.471500e+02 -1.283800e+02 +1 1932 8.112300e+02 -3.486700e+02 +2 1932 6.513101e+02 -1.866900e+02 +1 1933 -7.884100e+02 -3.492700e+02 +3 1933 -7.722800e+02 -2.602500e+02 +1 1934 -9.066900e+02 -3.227300e+02 +3 1934 -8.765200e+02 -2.310601e+02 +1 1935 -8.289800e+02 -3.065100e+02 +2 1935 -2.499900e+02 -1.771400e+02 +3 1935 -8.097100e+02 -2.159800e+02 +13 1935 -1.681620e+03 -1.692500e+02 +1 1936 -8.654500e+02 -3.043900e+02 +2 1936 -2.605200e+02 -1.775200e+02 +9 1936 -2.979900e+02 5.069946e+00 +11 1936 3.491400e+02 -5.013000e+01 +1 1937 8.637900e+02 -2.954301e+02 +2 1937 6.842900e+02 -1.592500e+02 +6 1937 7.533300e+02 -2.591900e+02 +1 1938 -1.212880e+03 -2.915900e+02 +6 1938 -7.547700e+02 -1.987200e+02 +7 1938 1.656000e+02 1.730601e+02 +9 1938 -4.063400e+02 -1.060059e+00 +12 1938 -9.479000e+02 -6.697200e+02 +1 1939 -1.212880e+03 -2.915900e+02 +6 1939 -7.547700e+02 -1.987200e+02 +1 1940 -1.095730e+03 -2.847400e+02 +6 1940 -6.718600e+02 -1.974600e+02 +1 1941 -1.126300e+03 -2.846200e+02 +2 1941 -3.561100e+02 -1.747600e+02 +1 1942 -1.126300e+03 -2.846200e+02 +2 1942 -3.561100e+02 -1.747600e+02 +7 1942 1.899500e+02 1.760100e+02 +9 1942 -3.762700e+02 3.150024e+00 +12 1942 -9.228000e+02 -6.665100e+02 +18 1942 -5.119700e+02 -1.136400e+02 +1 1943 8.943101e+02 -2.811200e+02 +3 1943 9.431001e+02 -1.793200e+02 +1 1944 8.943101e+02 -2.811200e+02 +3 1944 9.431001e+02 -1.793200e+02 +8 1944 7.666700e+02 -1.124700e+02 +1 1945 1.015840e+03 -2.767000e+02 +3 1945 1.078930e+03 -1.739600e+02 +1 1946 7.988899e+02 -2.655200e+02 +2 1946 6.426400e+02 -1.345000e+02 +1 1947 7.867500e+02 -2.581700e+02 +2 1947 6.358700e+02 -1.279000e+02 +3 1947 7.921000e+02 -1.589300e+02 +1 1948 1.370350e+03 -2.503101e+02 +7 1948 1.034440e+03 1.928800e+02 +9 1948 6.500200e+02 4.266003e+01 +17 1948 -6.466600e+02 1.169900e+02 +1 1949 8.531799e+02 -2.507000e+02 +2 1949 6.777400e+02 -1.318500e+02 +1 1950 9.671899e+02 -2.435300e+02 +2 1950 7.429301e+02 -1.306100e+02 +3 1950 1.022560e+03 -1.396800e+02 +7 1950 8.973401e+02 1.975100e+02 +17 1950 -9.754900e+02 1.298700e+02 +1 1951 7.867400e+02 -2.430800e+02 +2 1951 6.354200e+02 -1.203500e+02 +3 1951 7.921100e+02 -1.458500e+02 +1 1952 -1.972100e+02 -2.070500e+02 +3 1952 -3.340800e+02 -1.219100e+02 +10 1952 -7.989001e+01 -4.680100e+02 +13 1952 -1.058350e+03 1.028700e+02 +18 1952 -3.411000e+02 -3.902002e+01 +1 1953 -5.001000e+02 -1.964600e+02 +6 1953 -1.791500e+02 -1.609100e+02 +1 1954 -2.457300e+02 -1.838800e+02 +3 1954 -3.602500e+02 -9.997998e+01 +1 1955 5.356000e+02 -1.712400e+02 +3 1955 3.829000e+02 -8.764001e+01 +1 1956 3.382300e+02 -1.331000e+02 +2 1956 5.615997e+01 1.669300e+02 +13 1956 -1.838199e+02 6.213401e+02 +1 1957 7.733201e+02 -1.168800e+02 +2 1957 6.277200e+02 -4.559003e+01 +3 1957 7.785800e+02 -1.878003e+01 +12 1957 -2.791100e+02 -5.849000e+02 +17 1957 -1.165120e+03 2.617000e+02 +1 1958 -6.900024e+00 -1.059600e+02 +8 1958 6.485800e+02 9.352002e+01 +16 1958 8.170800e+02 3.796500e+02 +1 1959 -5.815100e+02 -1.042000e+02 +5 1959 6.213400e+02 6.329600e+02 +6 1959 -2.483800e+02 -9.289001e+01 +7 1959 3.444000e+02 2.558600e+02 +9 1959 -2.225400e+02 1.172600e+02 +11 1959 4.169800e+02 5.676001e+01 +1 1960 -3.396700e+02 -9.371997e+01 +3 1960 -4.193800e+02 -1.330017e+00 +1 1961 -7.581200e+02 -9.113000e+01 +2 1961 -2.287400e+02 -4.941998e+01 +3 1961 -7.543400e+02 1.267999e+01 +7 1961 2.910601e+02 2.504900e+02 +9 1961 -2.718000e+02 1.051300e+02 +10 1961 -2.061100e+02 -4.684500e+02 +13 1961 -1.614030e+03 1.449000e+02 +1 1962 8.103999e+02 -8.732996e+01 +2 1962 6.529000e+02 -3.250000e+01 +17 1962 -1.120110e+03 2.806000e+02 +1 1963 8.103999e+02 -8.732996e+01 +2 1963 6.529000e+02 -3.250000e+01 +17 1963 -1.120110e+03 2.806000e+02 +1 1964 -1.648400e+02 -7.619995e+01 +3 1964 -3.216200e+02 7.179993e+00 +9 1964 -1.192300e+02 2.220000e+02 +11 1964 5.024100e+02 1.582300e+02 +12 1964 -6.495000e+02 -4.975601e+02 +13 1964 -1.034500e+03 3.706300e+02 +1 1965 -4.069100e+02 -7.107996e+01 +8 1965 -1.505400e+02 6.902002e+01 +1 1966 1.395510e+03 -6.333997e+01 +7 1966 1.047030e+03 2.593800e+02 +9 1966 6.620100e+02 1.228500e+02 +13 1966 1.396680e+03 1.344199e+02 +1 1967 1.395510e+03 -6.333997e+01 +7 1967 1.047030e+03 2.593800e+02 +9 1967 6.620100e+02 1.228500e+02 +10 1967 4.594099e+02 -4.517700e+02 +12 1967 -9.168994e+01 -5.845200e+02 +13 1967 1.396680e+03 1.344199e+02 +18 1967 1.353300e+02 -5.318005e+01 +1 1968 -4.451000e+02 -5.787000e+01 +6 1968 -1.216400e+02 -6.860999e+01 +1 1969 -7.836300e+02 -5.270996e+01 +4 1969 9.332300e+02 2.613800e+02 +1 1970 1.259550e+03 -5.020996e+01 +7 1970 9.987600e+02 2.632500e+02 +10 1970 4.198501e+02 -4.489100e+02 +12 1970 -1.357400e+02 -5.792500e+02 +17 1970 -7.301700e+02 2.824299e+02 +18 1970 1.004700e+02 -4.889001e+01 +20 1970 9.315002e+01 -2.370400e+02 +1 1971 -5.291300e+02 -2.072998e+01 +3 1971 -5.596600e+02 8.009003e+01 +6 1971 -2.032800e+02 -3.723999e+01 +1 1972 7.702600e+02 -4.609985e+00 +2 1972 6.266899e+02 2.309998e+01 +3 1972 7.751200e+02 9.767999e+01 +6 1972 7.129399e+02 -4.782001e+01 +17 1972 -1.166990e+03 3.650100e+02 +1 1973 9.398799e+02 1.090027e+00 +6 1973 8.167300e+02 -4.396997e+01 +8 1973 8.056000e+02 1.212400e+02 +1 1974 -4.264000e+02 4.229980e+00 +3 1974 -4.885800e+02 1.042500e+02 +4 1974 1.081650e+03 3.013700e+02 +5 1974 7.094500e+02 7.018300e+02 +10 1974 -1.343800e+02 -4.135601e+02 +13 1974 -1.292170e+03 3.712100e+02 +1 1975 -1.078820e+03 4.090002e+01 +2 1975 -3.432100e+02 1.750000e+00 +10 1975 -2.780800e+02 -4.397300e+02 +12 1975 -9.101500e+02 -5.591100e+02 +18 1975 -5.047700e+02 -3.022998e+01 +1 1976 5.178500e+02 4.544995e+01 +3 1976 3.179600e+02 1.231700e+02 +6 1976 6.365100e+02 -2.433002e+01 +1 1977 7.808999e+02 5.356006e+01 +2 1977 6.331200e+02 5.560999e+01 +17 1977 -1.155790e+03 4.132200e+02 +1 1978 9.638101e+02 5.775000e+01 +2 1978 7.427300e+02 3.970001e+01 +3 1978 1.021940e+03 1.646300e+02 +17 1978 -9.760100e+02 3.868401e+02 +1 1979 7.687600e+02 8.294995e+01 +3 1979 7.735601e+02 1.839700e+02 +1 1980 7.687600e+02 8.294995e+01 +3 1980 7.735601e+02 1.839700e+02 +1 1981 8.575901e+02 8.762000e+01 +2 1981 6.827900e+02 6.164001e+01 +3 1981 9.008300e+02 1.928800e+02 +17 1981 -1.069560e+03 4.224600e+02 +1 1982 1.165930e+03 1.149199e+02 +6 1982 9.829900e+02 3.908002e+01 +17 1982 -8.030900e+02 4.222700e+02 +1 1983 7.328799e+02 1.198101e+02 +2 1983 6.053700e+02 9.626001e+01 +17 1983 -1.198380e+03 4.791200e+02 +1 1984 -5.666500e+02 1.464299e+02 +2 1984 -1.725700e+02 1.115300e+02 +3 1984 -5.945200e+02 2.560300e+02 +6 1984 -2.291000e+02 7.795001e+01 +9 1984 -2.213700e+02 2.371300e+02 +10 1984 -1.643600e+02 -3.781700e+02 +11 1984 4.188101e+02 1.736500e+02 +12 1984 -7.724000e+02 -4.831899e+02 +13 1984 -1.423160e+03 5.411599e+02 +18 1984 -4.089800e+02 2.981006e+01 +1 1985 -1.216790e+03 1.462600e+02 +7 1985 1.600300e+02 3.135100e+02 +11 1985 2.357400e+02 1.154400e+02 +1 1986 -5.568300e+02 1.552300e+02 +2 1986 -1.691400e+02 1.174000e+02 +3 1986 -5.862700e+02 2.666799e+02 +4 1986 1.018860e+03 3.358800e+02 +5 1986 6.194200e+02 7.383400e+02 +6 1986 -2.207800e+02 8.607001e+01 +7 1986 3.513199e+02 3.535200e+02 +9 1986 -2.183600e+02 2.413700e+02 +10 1986 -1.620699e+02 -3.747700e+02 +11 1986 4.216000e+02 1.779400e+02 +12 1986 -7.692800e+02 -4.794000e+02 +13 1986 -1.412020e+03 5.554099e+02 +18 1986 -4.067400e+02 3.270996e+01 +20 1986 -3.440300e+02 -1.686600e+02 +1 1987 -1.290950e+03 1.605601e+02 +6 1987 -7.944000e+02 1.110400e+02 +1 1988 -1.289430e+03 1.856899e+02 +2 1988 -4.407300e+02 7.450000e+01 +1 1989 -8.714700e+02 1.879900e+02 +6 1989 -4.831700e+02 1.198600e+02 +1 1990 8.721699e+02 1.968700e+02 +2 1990 6.920900e+02 1.230200e+02 +3 1990 9.185400e+02 3.067600e+02 +17 1990 -1.054910e+03 5.148700e+02 +1 1991 1.379390e+03 2.004099e+02 +7 1991 1.045960e+03 3.545901e+02 +9 1991 6.579600e+02 2.369399e+02 +10 1991 4.548401e+02 -3.705300e+02 +12 1991 -9.352002e+01 -4.957200e+02 +13 1991 1.389180e+03 4.988900e+02 +17 1991 -6.296899e+02 4.876799e+02 +18 1991 1.344200e+02 1.670996e+01 +1 1992 -1.143840e+03 2.253500e+02 +2 1992 -3.763300e+02 1.011300e+02 +7 1992 1.792600e+02 3.407800e+02 +11 1992 2.597800e+02 1.499200e+02 +1 1993 1.386160e+03 2.262600e+02 +7 1993 1.047290e+03 3.634800e+02 +9 1993 6.599800e+02 2.476000e+02 +10 1993 4.557000e+02 -3.625200e+02 +12 1993 -9.279004e+01 -4.868500e+02 +13 1993 1.395850e+03 5.353000e+02 +17 1993 -6.258199e+02 5.086899e+02 +20 1993 1.221899e+02 -1.739301e+02 +1 1994 -1.302820e+03 2.278900e+02 +2 1994 -4.491600e+02 9.720996e+01 +8 1994 -1.015160e+03 2.559500e+02 +9 1994 -4.493000e+02 2.082200e+02 +11 1994 2.072500e+02 1.452600e+02 +1 1995 -5.943300e+02 2.309299e+02 +3 1995 -6.202200e+02 3.468600e+02 +6 1995 -2.507900e+02 1.379600e+02 +1 1996 -1.193560e+03 2.306699e+02 +7 1996 1.648300e+02 3.408700e+02 +10 1996 -3.091400e+02 -3.856200e+02 +11 1996 2.440500e+02 1.497700e+02 +1 1997 -6.341300e+02 2.465100e+02 +3 1997 -6.539000e+02 3.651000e+02 +6 1997 -2.828200e+02 1.493500e+02 +1 1998 9.558899e+02 2.501400e+02 +2 1998 7.400500e+02 1.485000e+02 +3 1998 1.012860e+03 3.604399e+02 +6 1998 8.309399e+02 1.409900e+02 +17 1998 -9.791700e+02 5.533301e+02 +1 1999 1.120540e+03 2.689500e+02 +6 1999 9.529500e+02 1.549700e+02 +8 1999 9.326600e+02 3.499600e+02 +12 1999 -1.767600e+02 -4.687100e+02 +1 2000 -6.894900e+02 2.683900e+02 +5 2000 5.473800e+02 7.602600e+02 +6 2000 -3.292400e+02 1.668100e+02 +1 2001 -5.754800e+02 2.711599e+02 +3 2001 -6.037800e+02 3.900100e+02 +6 2001 -2.341200e+02 1.651400e+02 +1 2002 8.190901e+02 2.725601e+02 +2 2002 6.599600e+02 1.751500e+02 +3 2002 8.482100e+02 3.809900e+02 +17 2002 -1.108370e+03 5.983700e+02 +1 2003 8.498601e+02 2.741799e+02 +2 2003 6.791600e+02 1.711700e+02 +6 2003 7.597300e+02 1.573700e+02 +17 2003 -1.075830e+03 5.896799e+02 +1 2004 9.456101e+02 2.799700e+02 +2 2004 7.341700e+02 1.679100e+02 +3 2004 1.000520e+03 3.930100e+02 +17 2004 -9.878200e+02 5.821899e+02 +1 2005 8.879299e+02 2.841000e+02 +2 2005 7.014000e+02 1.731200e+02 +3 2005 9.346101e+02 3.946300e+02 +7 2005 8.792400e+02 3.927100e+02 +8 2005 7.703199e+02 3.636500e+02 +17 2005 -1.039290e+03 5.914600e+02 +1 2006 -4.036100e+02 2.888700e+02 +2 2006 -1.284300e+02 2.331400e+02 +3 2006 -4.697600e+02 3.954600e+02 +1 2007 -5.679300e+02 2.903700e+02 +3 2007 -5.973200e+02 4.072000e+02 +6 2007 -2.265100e+02 1.767100e+02 +1 2008 -5.967000e+02 3.088500e+02 +6 2008 -2.487400e+02 1.903900e+02 +1 2009 -4.417300e+02 3.188000e+02 +6 2009 -1.151600e+02 1.911900e+02 +1 2010 -4.417300e+02 3.188000e+02 +6 2010 -1.151600e+02 1.911900e+02 +1 2011 1.208240e+03 3.385000e+02 +7 2011 9.872000e+02 4.060200e+02 +12 2011 -1.485000e+02 -4.464399e+02 +17 2011 -7.639300e+02 6.115801e+02 +1 2012 -7.419300e+02 3.527200e+02 +2 2012 -2.296600e+02 2.069800e+02 +10 2012 -2.047400e+02 -3.267400e+02 +13 2012 -1.600800e+03 7.866000e+02 +1 2013 1.379470e+03 3.545901e+02 +7 2013 1.049540e+03 4.116799e+02 +9 2013 6.606101e+02 3.056000e+02 +10 2013 4.548201e+02 -3.216200e+02 +13 2013 1.400440e+03 7.192900e+02 +17 2013 -6.265200e+02 6.195000e+02 +18 2013 1.363101e+02 5.948999e+01 +20 2013 1.229500e+02 -1.432400e+02 +1 2014 8.623000e+02 3.588500e+02 +2 2014 6.863199e+02 2.181800e+02 +1 2015 -6.917700e+02 3.641300e+02 +6 2015 -3.274400e+02 2.324300e+02 +1 2016 -4.193500e+02 3.711100e+02 +3 2016 -4.854100e+02 4.831600e+02 +1 2017 -1.453410e+03 3.995701e+02 +2 2017 -5.282300e+02 1.880300e+02 +5 2017 2.630400e+02 7.254200e+02 +6 2017 -8.964400e+02 2.747800e+02 +7 2017 8.670996e+01 3.907000e+02 +9 2017 -5.103600e+02 2.755200e+02 +10 2017 -3.802900e+02 -3.396600e+02 +11 2017 1.496801e+02 2.097700e+02 +12 2017 -1.022790e+03 -4.473500e+02 +18 2017 -5.930600e+02 5.778003e+01 +1 2018 1.417810e+03 4.013700e+02 +7 2018 1.062420e+03 4.276100e+02 +9 2018 6.765801e+02 3.243401e+02 +10 2018 4.654500e+02 -3.081200e+02 +13 2018 1.450930e+03 7.792200e+02 +17 2018 -5.942000e+02 6.554200e+02 +20 2018 1.308500e+02 -1.334600e+02 +1 2019 -6.072200e+02 4.737600e+02 +3 2019 -6.781800e+02 5.913600e+02 +6 2019 -2.200500e+02 2.979000e+02 +7 2019 3.234200e+02 4.947200e+02 +10 2019 -1.984500e+02 -2.494200e+02 +13 2019 -1.569630e+03 1.129190e+03 +1 2020 -6.072200e+02 4.737600e+02 +3 2020 -6.781800e+02 5.913600e+02 +6 2020 -2.200500e+02 2.979000e+02 +13 2020 -1.569630e+03 1.129190e+03 +1 2021 6.873899e+02 4.957400e+02 +3 2021 5.797500e+02 5.856899e+02 +1 2022 6.990200e+02 5.026899e+02 +2 2022 5.614301e+02 4.198600e+02 +3 2022 5.940200e+02 5.931000e+02 +6 2022 7.317000e+02 3.048700e+02 +7 2022 8.800601e+02 5.569500e+02 +16 2022 9.767700e+02 5.313600e+02 +17 2022 -1.308470e+03 9.867100e+02 +1 2023 8.446699e+02 5.048400e+02 +2 2023 6.605601e+02 4.182400e+02 +17 2023 -1.151940e+03 9.750400e+02 +1 2024 9.065000e+02 5.128300e+02 +3 2024 7.990000e+02 5.999600e+02 +1 2025 9.065000e+02 5.128300e+02 +3 2025 7.990000e+02 5.999600e+02 +1 2026 8.076299e+02 5.372600e+02 +2 2026 6.357700e+02 4.415000e+02 +17 2026 -1.193120e+03 1.013210e+03 +1 2027 -9.014500e+02 5.562100e+02 +6 2027 -4.994400e+02 3.719800e+02 +1 2028 -1.169860e+03 5.802500e+02 +6 2028 -6.974800e+02 3.947500e+02 +1 2029 -1.135370e+03 5.889399e+02 +6 2029 -6.732100e+02 3.996300e+02 +7 2029 1.791100e+02 4.605701e+02 +8 2029 -8.927000e+02 5.326700e+02 +10 2029 -2.969500e+02 -2.774000e+02 +11 2029 2.593000e+02 2.961500e+02 +1 2030 -1.214670e+03 6.148400e+02 +6 2030 -7.267900e+02 4.173600e+02 +7 2030 1.557000e+02 4.665801e+02 +8 2030 -9.523100e+02 5.492700e+02 +1 2031 -1.326370e+03 6.473201e+02 +2 2031 -4.690500e+02 3.267600e+02 +5 2031 2.867700e+02 8.174000e+02 +6 2031 -8.043300e+02 4.412500e+02 +7 2031 1.219600e+02 4.738201e+02 +9 2031 -4.672200e+02 3.818800e+02 +11 2031 1.916200e+02 3.118700e+02 +1 2032 -9.223600e+02 6.479200e+02 +8 2032 -7.231000e+02 5.942000e+02 +1 2033 -1.327090e+03 6.782800e+02 +2 2033 -4.692100e+02 3.432800e+02 +7 2033 1.216200e+02 4.840701e+02 +11 2033 1.912200e+02 3.241500e+02 +1 2034 -1.169830e+03 7.005300e+02 +2 2034 -3.919400e+02 3.600400e+02 +5 2034 3.331200e+02 8.485300e+02 +7 2034 1.688500e+02 4.950100e+02 +8 2034 -9.224600e+02 6.151600e+02 +9 2034 -4.082400e+02 4.086799e+02 +11 2034 2.478400e+02 3.384000e+02 +1 2035 -1.138270e+03 7.039700e+02 +2 2035 -3.774500e+02 3.630000e+02 +7 2035 1.783300e+02 4.974199e+02 +8 2035 -8.983800e+02 6.191300e+02 +9 2035 -3.966100e+02 4.115000e+02 +11 2035 2.590100e+02 3.415200e+02 +12 2035 -9.248900e+02 -3.428500e+02 +1 2036 -1.392580e+03 7.128101e+02 +2 2036 -5.019100e+02 3.590900e+02 +1 2037 -1.270260e+03 7.215300e+02 +2 2037 -4.392000e+02 3.662500e+02 +5 2037 2.994100e+02 8.460500e+02 +7 2037 1.391300e+02 4.981300e+02 +8 2037 -9.967000e+02 6.242800e+02 +9 2037 -4.449900e+02 4.120400e+02 +11 2037 2.128400e+02 3.413201e+02 +1 2038 -1.302690e+03 7.248101e+02 +2 2038 -4.550600e+02 3.671900e+02 +7 2038 1.294600e+02 4.981899e+02 +9 2038 -4.575200e+02 4.126799e+02 +10 2038 -3.404399e+02 -2.428000e+02 +11 2038 2.015900e+02 3.416200e+02 +1 2039 -1.319290e+03 7.259800e+02 +5 2039 2.831100e+02 8.432000e+02 +1 2040 -1.427870e+03 7.325200e+02 +2 2040 -5.187900e+02 3.696900e+02 +1 2041 -1.211000e+03 -6.047000e+02 +6 2041 -7.619200e+02 -4.137200e+02 +1 2042 -5.552600e+02 -5.806600e+02 +6 2042 -2.385100e+02 -4.218400e+02 +1 2043 9.863000e+01 -5.773400e+02 +3 2043 5.640300e+02 -4.857500e+02 +1 2044 9.810999e+01 -5.688199e+02 +3 2044 5.582500e+02 -4.773300e+02 +1 2045 -9.565800e+02 -5.663700e+02 +3 2045 -9.189500e+02 -4.904301e+02 +1 2046 -8.978600e+02 -5.623300e+02 +3 2046 -8.630800e+02 -4.841400e+02 +1 2047 1.221200e+02 -5.424900e+02 +3 2047 5.927700e+02 -4.467500e+02 +6 2047 -6.542999e+01 -4.002700e+02 +1 2048 -5.547300e+02 -5.417600e+02 +6 2048 -2.381600e+02 -3.967100e+02 +1 2049 9.078899e+02 -4.947300e+02 +8 2049 7.718400e+02 -2.907100e+02 +1 2050 7.813201e+02 -4.869399e+02 +3 2050 7.862100e+02 -3.890699e+02 +1 2051 -8.860900e+02 -4.436700e+02 +3 2051 -8.570400e+02 -3.595300e+02 +6 2051 -5.133200e+02 -3.140300e+02 +1 2052 -9.897700e+02 -4.438400e+02 +6 2052 -5.942900e+02 -3.108000e+02 +9 2052 -3.321300e+02 -5.682996e+01 +1 2053 -1.003480e+03 -4.437300e+02 +6 2053 -6.048200e+02 -3.103000e+02 +1 2054 -1.034120e+03 -4.438600e+02 +6 2054 -6.283900e+02 -3.094500e+02 +1 2055 -1.018770e+03 -4.419500e+02 +6 2055 -6.168500e+02 -3.083500e+02 +9 2055 -3.416400e+02 -5.694995e+01 +1 2056 -8.954800e+02 -4.390699e+02 +3 2056 -8.655400e+02 -3.551801e+02 +1 2057 -9.981500e+02 -4.365800e+02 +6 2057 -6.005000e+02 -3.054500e+02 +9 2057 -3.351100e+02 -5.410999e+01 +1 2058 -1.009890e+03 -4.364800e+02 +6 2058 -6.102000e+02 -3.049000e+02 +1 2059 -1.009890e+03 -4.364800e+02 +6 2059 -6.102000e+02 -3.049000e+02 +9 2059 -3.389399e+02 -5.446997e+01 +1 2060 -7.591100e+02 -4.214301e+02 +3 2060 -7.472500e+02 -3.353800e+02 +1 2061 -5.412100e+02 -4.144900e+02 +6 2061 -2.200500e+02 -3.085300e+02 +1 2062 -4.525500e+02 -3.886500e+02 +2 2062 -1.390200e+02 -2.051200e+02 +6 2062 -1.409000e+02 -2.961800e+02 +1 2063 -3.723000e+02 -3.845699e+02 +3 2063 -4.418700e+02 -2.986600e+02 +1 2064 8.729004e+01 -3.819500e+02 +3 2064 5.484399e+02 -2.696801e+02 +1 2065 9.057900e+02 -3.801600e+02 +3 2065 9.552100e+02 -2.807300e+02 +1 2066 8.338401e+02 -3.792200e+02 +2 2066 6.653800e+02 -2.047500e+02 +1 2067 9.142800e+02 -3.758800e+02 +2 2067 7.124100e+02 -2.052500e+02 +3 2067 9.640901e+02 -2.760300e+02 +6 2067 7.886000e+02 -3.197500e+02 +8 2067 7.793000e+02 -1.928500e+02 +1 2068 -3.297800e+02 -3.760800e+02 +3 2068 -4.087800e+02 -2.904399e+02 +1 2069 7.921799e+02 -3.744600e+02 +2 2069 6.379800e+02 -1.982700e+02 +1 2070 8.109900e+02 -3.727100e+02 +2 2070 6.511899e+02 -1.995900e+02 +1 2071 8.380901e+02 -3.706300e+02 +2 2071 6.680300e+02 -1.998500e+02 +1 2072 1.441100e+02 -3.577200e+02 +3 2072 6.161899e+02 -2.406400e+02 +6 2072 -4.453998e+01 -2.615900e+02 +1 2073 -8.393700e+02 -3.563700e+02 +6 2073 -4.692800e+02 -2.560900e+02 +1 2074 -5.629800e+02 -3.490601e+02 +6 2074 -2.398200e+02 -2.629700e+02 +1 2075 1.607700e+02 -3.486100e+02 +6 2075 -3.092999e+01 -2.552800e+02 +1 2076 1.516700e+02 -3.492200e+02 +6 2076 -3.840997e+01 -2.552400e+02 +1 2077 1.347200e+02 -3.492200e+02 +3 2077 6.073900e+02 -2.311400e+02 +1 2078 9.738000e+01 -3.492900e+02 +3 2078 5.647100e+02 -2.319000e+02 +1 2079 -1.102200e+02 -3.455500e+02 +3 2079 -2.704000e+02 -2.620300e+02 +8 2079 2.729500e+02 -1.532000e+02 +1 2080 -6.739000e+02 -3.330200e+02 +7 2080 3.170601e+02 1.700100e+02 +1 2081 -7.547700e+02 -3.212900e+02 +2 2081 -2.263000e+02 -1.816000e+02 +9 2081 -2.686100e+02 4.510010e+00 +11 2081 3.758101e+02 -5.051001e+01 +1 2082 -8.355900e+02 -3.154100e+02 +2 2082 -2.523400e+02 -1.817100e+02 +13 2082 -1.688630e+03 -1.803600e+02 +1 2083 -2.865002e+01 -3.144200e+02 +6 2083 3.228900e+02 -2.700800e+02 +1 2084 -1.483400e+02 -3.114000e+02 +3 2084 -2.978100e+02 -2.271200e+02 +1 2085 1.152510e+03 -3.103800e+02 +6 2085 9.622700e+02 -2.771200e+02 +8 2085 9.415500e+02 -1.390500e+02 +12 2085 -1.744800e+02 -6.666000e+02 +17 2085 -8.208100e+02 6.791003e+01 +1 2086 -1.856500e+02 -3.094900e+02 +3 2086 -3.230400e+02 -2.260300e+02 +1 2087 -8.054700e+02 -3.093199e+02 +2 2087 -2.432300e+02 -1.766600e+02 +3 2087 -7.899300e+02 -2.174800e+02 +6 2087 -4.428200e+02 -2.248700e+02 +9 2087 -2.828000e+02 7.170044e+00 +13 2087 -1.660420e+03 -1.689301e+02 +1 2088 1.411030e+03 -3.067800e+02 +7 2088 1.046420e+03 1.722000e+02 +9 2088 6.644800e+02 1.839001e+01 +12 2088 -9.080005e+01 -6.659000e+02 +17 2088 -6.156500e+02 6.985999e+01 +1 2089 7.781101e+02 -3.066000e+02 +2 2089 6.300699e+02 -1.574700e+02 +3 2089 7.836600e+02 -2.082800e+02 +1 2090 1.058990e+03 -3.028000e+02 +6 2090 8.912900e+02 -2.687000e+02 +1 2091 7.983301e+02 -3.025300e+02 +2 2091 6.447200e+02 -1.594100e+02 +1 2092 -1.219120e+03 -3.012500e+02 +2 2092 -3.989100e+02 -1.853500e+02 +11 2092 2.450100e+02 -5.903998e+01 +1 2093 -1.079390e+03 -2.865699e+02 +6 2093 -6.599600e+02 -1.993400e+02 +1 2094 -2.108600e+02 -2.495900e+02 +6 2094 9.114001e+01 -2.119600e+02 +1 2095 -1.195800e+02 -2.461400e+02 +2 2095 -6.440997e+01 -7.075000e+01 +3 2095 -2.807900e+02 -1.611500e+02 +4 2095 1.282190e+03 2.430601e+02 +5 2095 9.768000e+02 6.520701e+02 +6 2095 1.755601e+02 -2.139200e+02 +8 2095 2.621200e+02 -6.600000e+01 +10 2095 -5.779004e+01 -4.764100e+02 +11 2095 5.250500e+02 6.079999e+01 +12 2095 -6.305800e+02 -5.775100e+02 +13 2095 -9.615700e+02 5.812000e+01 +16 2095 7.005900e+02 2.727900e+02 +18 2095 -3.228500e+02 -4.460999e+01 +20 2095 -2.731899e+02 -2.354000e+02 +1 2096 -2.081100e+02 -2.404600e+02 +6 2096 9.556995e+01 -2.052700e+02 +1 2097 5.443899e+02 -2.346300e+02 +2 2097 4.354399e+02 -7.640002e+01 +3 2097 4.006000e+02 -1.551800e+02 +11 2097 9.338600e+02 5.892999e+01 +17 2097 -1.527430e+03 2.172700e+02 +1 2098 3.428300e+02 -2.010400e+02 +2 2098 6.229999e+01 9.235999e+01 +3 2098 -1.909998e+01 -1.324700e+02 +11 2098 7.031200e+02 2.718300e+02 +13 2098 -1.719200e+02 4.317900e+02 +18 2098 -1.603300e+02 8.902002e+01 +20 2098 -1.368199e+02 -1.195100e+02 +1 2099 -5.189800e+02 -2.013500e+02 +3 2099 -5.517000e+02 -1.073500e+02 +6 2099 -1.977800e+02 -1.628900e+02 +13 2099 -1.375660e+03 2.406006e+01 +1 2100 -1.503600e+02 -1.974500e+02 +3 2100 -3.003000e+02 -1.132800e+02 +10 2100 -6.654004e+01 -4.599700e+02 +11 2100 5.166700e+02 8.110999e+01 +13 2100 -9.986500e+02 1.351400e+02 +18 2100 -3.304200e+02 -3.022998e+01 +1 2101 -5.328900e+02 -1.985100e+02 +6 2101 -2.093500e+02 -1.606100e+02 +1 2102 8.500500e+02 -1.974700e+02 +2 2102 6.765500e+02 -1.013000e+02 +1 2103 9.488201e+02 -1.868800e+02 +2 2103 7.318300e+02 -9.927002e+01 +1 2104 -3.399100e+02 -1.825400e+02 +3 2104 -4.196700e+02 -9.283002e+01 +13 2104 -1.195830e+03 9.110999e+01 +1 2105 -4.083600e+02 -1.833900e+02 +3 2105 -4.702600e+02 -9.262000e+01 +1 2106 -6.609900e+02 -1.693300e+02 +6 2106 -3.127400e+02 -1.347700e+02 +1 2107 -4.994600e+02 -1.572100e+02 +6 2107 -1.772200e+02 -1.335600e+02 +1 2108 6.460100e+02 -1.535200e+02 +2 2108 5.362400e+02 -4.607001e+01 +17 2108 -1.328950e+03 2.639500e+02 +1 2109 7.106599e+02 -1.532300e+02 +2 2109 5.881700e+02 -6.322998e+01 +3 2109 7.040100e+02 -5.697998e+01 +17 2109 -1.231040e+03 2.338900e+02 +1 2110 -5.085500e+02 -1.519200e+02 +3 2110 -5.455700e+02 -5.683002e+01 +13 2110 -1.367140e+03 1.013600e+02 +1 2111 -5.085500e+02 -1.519200e+02 +3 2111 -5.455700e+02 -5.683002e+01 +1 2112 -1.956006e+01 -1.504500e+02 +8 2112 6.343101e+02 4.988000e+01 +1 2113 -8.288100e+02 -1.484200e+02 +3 2113 -8.142100e+02 -4.591998e+01 +6 2113 -4.570600e+02 -1.146800e+02 +1 2114 6.609800e+02 -1.427000e+02 +2 2114 5.496200e+02 -4.491998e+01 +17 2114 -1.302320e+03 2.636799e+02 +1 2115 3.409700e+02 -1.432500e+02 +2 2115 6.037000e+01 1.561300e+02 +3 2115 -2.065002e+01 -7.585999e+01 +11 2115 7.019800e+02 3.296000e+02 +12 2115 -3.369700e+02 -3.627600e+02 +13 2115 -1.742400e+02 5.933401e+02 +1 2116 -8.660600e+02 -1.434200e+02 +6 2116 -4.881300e+02 -1.093500e+02 +1 2117 5.572000e+02 -1.389600e+02 +2 2117 4.504800e+02 -7.349976e+00 +3 2117 4.250000e+02 -5.083002e+01 +11 2117 9.437900e+02 1.100900e+02 +17 2117 -1.496340e+03 3.250300e+02 +1 2118 2.932000e+02 -1.389900e+02 +2 2118 1.097998e+01 1.589500e+02 +3 2118 -6.555005e+01 -7.309998e+01 +11 2118 6.560900e+02 3.312900e+02 +13 2118 -3.039900e+02 6.028401e+02 +1 2119 -8.833000e+02 -1.388900e+02 +3 2119 -8.619400e+02 -3.509003e+01 +1 2120 -8.119000e+02 -1.259000e+02 +2 2120 -2.468700e+02 -7.303003e+01 +11 2120 3.592900e+02 2.833002e+01 +13 2120 -1.667870e+03 8.954004e+01 +1 2121 5.491399e+02 -1.240900e+02 +2 2121 4.437800e+02 6.250000e+00 +11 2121 9.388101e+02 1.229800e+02 +1 2122 7.815701e+02 -1.100000e+02 +2 2122 6.328300e+02 -4.090002e+01 +3 2122 7.877000e+02 -1.053003e+01 +17 2122 -1.157290e+03 2.674600e+02 +1 2123 5.582400e+02 -1.080699e+02 +2 2123 4.513000e+02 1.442999e+01 +3 2123 4.256100e+02 -2.032001e+01 +11 2123 9.444100e+02 1.277600e+02 +17 2123 -1.495570e+03 3.593800e+02 +1 2124 -9.268500e+02 -1.062300e+02 +2 2124 -2.817300e+02 -7.123999e+01 +9 2124 -3.171500e+02 8.482996e+01 +10 2124 -2.409301e+02 -4.799800e+02 +11 2124 3.318300e+02 2.665997e+01 +18 2124 -4.734200e+02 -6.415002e+01 +1 2125 8.299800e+02 -1.039301e+02 +3 2125 8.613199e+02 -2.940002e+00 +17 2125 -1.101710e+03 2.589199e+02 +1 2126 -9.388700e+02 -1.043101e+02 +2 2126 -2.863400e+02 -7.045001e+01 +1 2127 3.270200e+02 -1.032800e+02 +2 2127 4.554999e+01 1.979500e+02 +3 2127 -3.372998e+01 -3.878003e+01 +11 2127 6.888800e+02 3.669600e+02 +13 2127 -2.100900e+02 7.018700e+02 +1 2128 5.671201e+02 -9.889001e+01 +2 2128 4.583400e+02 2.122998e+01 +3 2128 4.353000e+02 -1.094000e+01 +17 2128 -1.485090e+03 3.696400e+02 +1 2129 1.315990e+03 -8.677002e+01 +7 2129 1.018390e+03 2.513600e+02 +9 2129 6.271101e+02 1.127400e+02 +17 2129 -6.857500e+02 2.519000e+02 +1 2130 -2.245400e+02 -8.366003e+01 +6 2130 8.054004e+01 -9.641998e+01 +1 2131 8.346399e+02 -7.681995e+01 +2 2131 6.673101e+02 -3.103003e+01 +17 2131 -1.095290e+03 2.822100e+02 +1 2132 -3.832400e+02 -6.422998e+01 +2 2132 -1.246600e+02 9.500000e+00 +11 2132 4.622500e+02 1.054400e+02 +1 2133 -5.231000e+02 -4.431995e+01 +3 2133 -5.572300e+02 5.595001e+01 +6 2133 -1.953500e+02 -5.441998e+01 +13 2133 -1.379210e+03 2.633000e+02 +1 2134 -1.112080e+03 -3.538000e+01 +7 2134 1.930200e+02 2.555300e+02 +9 2134 -3.738199e+02 1.044399e+02 +1 2135 -1.352810e+03 -8.880005e+00 +7 2135 1.216300e+02 2.605500e+02 +9 2135 -4.618700e+02 1.094100e+02 +12 2135 -9.905000e+02 -5.803000e+02 +1 2136 -6.352300e+02 -6.130005e+00 +2 2136 -1.937400e+02 1.116998e+01 +5 2136 5.878900e+02 6.630601e+02 +6 2136 -2.924300e+02 -2.352002e+01 +11 2136 4.014500e+02 9.565997e+01 +13 2136 -1.494640e+03 2.934600e+02 +20 2136 -3.575500e+02 -2.152200e+02 +1 2137 -1.481899e+02 -2.080017e+00 +6 2137 1.818900e+02 -4.909003e+01 +1 2138 7.624399e+02 4.969971e+00 +3 2138 7.661600e+02 1.050500e+02 +1 2139 -1.106520e+03 8.099976e+00 +2 2139 -3.518300e+02 -1.682001e+01 +3 2139 -1.077550e+03 1.248300e+02 +10 2139 -2.828000e+02 -4.501500e+02 +11 2139 2.787600e+02 6.408002e+01 +12 2139 -9.168600e+02 -5.705300e+02 +1 2140 9.669600e+02 2.381006e+01 +2 2140 7.447200e+02 1.932001e+01 +3 2140 1.024990e+03 1.308700e+02 +1 2141 8.444700e+02 2.890991e+01 +2 2141 6.739800e+02 3.052002e+01 +3 2141 8.800800e+02 1.307000e+02 +17 2141 -1.084950e+03 3.744900e+02 +1 2142 -7.832996e+01 3.284998e+01 +2 2142 -7.527002e+01 1.598600e+02 +11 2142 5.219600e+02 2.529800e+02 +13 2142 -9.288900e+02 6.395601e+02 +1 2143 -1.101960e+03 3.415991e+01 +7 2143 1.944700e+02 2.789399e+02 +1 2144 -1.534301e+02 3.941992e+01 +6 2144 1.802400e+02 -1.964001e+01 +1 2145 9.263799e+02 4.605005e+01 +2 2145 7.214200e+02 3.428003e+01 +3 2145 9.748899e+02 1.528700e+02 +17 2145 -1.009650e+03 3.799500e+02 +1 2146 -3.729600e+02 6.634009e+01 +3 2146 -4.481000e+02 1.641200e+02 +7 2146 4.140400e+02 3.415400e+02 +1 2147 7.795601e+02 7.800000e+01 +3 2147 7.841500e+02 1.799600e+02 +1 2148 8.683501e+02 8.790991e+01 +6 2148 7.669000e+02 1.991998e+01 +1 2149 9.650000e+02 1.026699e+02 +3 2149 1.022880e+03 2.088201e+02 +6 2149 8.341200e+02 3.194000e+01 +17 2149 -9.725600e+02 4.226899e+02 +1 2150 -5.234600e+02 1.117500e+02 +6 2150 -1.927300e+02 5.271002e+01 +1 2151 1.163130e+03 1.263800e+02 +6 2151 9.813800e+02 4.863000e+01 +9 2151 5.649900e+02 2.048800e+02 +17 2151 -8.058500e+02 4.314500e+02 +1 2152 -6.635000e+02 1.372700e+02 +7 2152 3.161801e+02 3.406500e+02 +1 2153 -5.541900e+02 1.426300e+02 +6 2153 -2.183900e+02 7.512000e+01 +7 2153 3.518600e+02 3.495300e+02 +1 2154 -1.900100e+02 1.447800e+02 +6 2154 1.611899e+02 5.252002e+01 +8 2154 2.625300e+02 3.015701e+02 +1 2155 1.376370e+03 1.463101e+02 +7 2155 1.043410e+03 3.349500e+02 +9 2155 6.572100e+02 2.137500e+02 +12 2155 -9.550000e+01 -5.127900e+02 +13 2155 1.383840e+03 4.268401e+02 +17 2155 -6.336400e+02 4.442600e+02 +1 2156 -1.318750e+03 1.553500e+02 +6 2156 -8.134300e+02 1.073300e+02 +1 2157 -1.212820e+03 1.559000e+02 +2 2157 -4.062500e+02 6.094000e+01 +1 2158 -5.676300e+02 1.658900e+02 +3 2158 -5.965300e+02 2.765601e+02 +4 2158 1.014650e+03 3.376599e+02 +5 2158 6.138600e+02 7.402300e+02 +6 2158 -2.298700e+02 9.196997e+01 +10 2158 -1.649700e+02 -3.720400e+02 +11 2158 4.180300e+02 1.824900e+02 +13 2158 -1.424740e+03 5.707400e+02 +1 2159 7.574900e+02 1.714399e+02 +2 2159 6.192100e+02 1.289800e+02 +3 2159 7.606300e+02 2.759000e+02 +17 2159 -1.178130e+03 5.282800e+02 +1 2160 -1.048620e+03 1.716899e+02 +3 2160 -1.027080e+03 3.010100e+02 +1 2161 7.747300e+02 1.734800e+02 +2 2161 6.300200e+02 1.300100e+02 +3 2161 7.788500e+02 2.775601e+02 +17 2161 -1.161960e+03 5.294500e+02 +1 2162 -7.911000e+02 1.761599e+02 +2 2162 -2.459000e+02 1.019200e+02 +13 2162 -1.653090e+03 5.234600e+02 +1 2163 -1.179530e+03 1.772100e+02 +2 2163 -3.905600e+02 7.322998e+01 +1 2164 -5.758900e+02 1.794199e+02 +2 2164 -1.774300e+02 1.308000e+02 +7 2164 3.447900e+02 3.610500e+02 +9 2164 -2.250699e+02 2.513900e+02 +1 2165 7.570100e+02 1.877400e+02 +2 2165 6.192500e+02 1.382300e+02 +3 2165 7.599800e+02 2.913600e+02 +6 2165 7.072400e+02 9.100000e+01 +17 2165 -1.178220e+03 5.429700e+02 +1 2166 7.752400e+02 1.885000e+02 +2 2166 6.302500e+02 1.394600e+02 +3 2166 7.792600e+02 2.922700e+02 +17 2166 -1.161460e+03 5.439299e+02 +1 2167 -6.726700e+02 1.907300e+02 +3 2167 -6.915600e+02 3.084399e+02 +7 2167 3.133300e+02 3.595500e+02 +10 2167 -1.914700e+02 -3.695100e+02 +12 2167 -8.046800e+02 -4.749500e+02 +13 2167 -1.544930e+03 5.845200e+02 +1 2168 -1.448200e+03 2.022700e+02 +6 2168 -9.000400e+02 1.410200e+02 +1 2169 -4.408500e+02 2.068500e+02 +6 2169 -1.142100e+02 1.137600e+02 +1 2170 -4.933600e+02 2.079500e+02 +6 2170 -1.609900e+02 1.165900e+02 +1 2171 8.189299e+02 2.225801e+02 +2 2171 6.595400e+02 1.466000e+02 +3 2171 8.470100e+02 3.302200e+02 +17 2171 -1.109000e+03 5.531500e+02 +1 2172 -4.269500e+02 2.275901e+02 +6 2172 -1.014300e+02 1.274400e+02 +1 2173 -4.269500e+02 2.275901e+02 +3 2173 -4.903800e+02 3.340800e+02 +6 2173 -1.014300e+02 1.274400e+02 +10 2173 -1.349800e+02 -3.338600e+02 +12 2173 -7.324200e+02 -4.289000e+02 +1 2174 -1.270650e+03 2.289700e+02 +6 2174 -7.796800e+02 1.570600e+02 +1 2175 -1.270650e+03 2.289700e+02 +6 2175 -7.796800e+02 1.570600e+02 +1 2176 -1.172280e+03 2.347600e+02 +2 2176 -3.892800e+02 1.048000e+02 +9 2176 -4.040800e+02 2.145300e+02 +11 2176 2.515699e+02 1.519300e+02 +1 2177 -1.460370e+03 2.460601e+02 +2 2177 -5.286300e+02 1.042700e+02 +9 2177 -5.107400e+02 2.119299e+02 +1 2178 6.273201e+02 2.520000e+02 +2 2178 5.118300e+02 2.445800e+02 +3 2178 5.267100e+02 3.419900e+02 +17 2178 -1.385550e+03 7.155701e+02 +1 2179 -5.039800e+02 2.690500e+02 +6 2179 -1.747300e+02 1.606000e+02 +1 2180 8.120000e+02 2.818900e+02 +2 2180 6.552800e+02 1.832000e+02 +1 2181 7.548501e+02 2.824000e+02 +2 2181 6.191100e+02 1.951800e+02 +3 2181 7.596899e+02 3.878400e+02 +1 2182 7.548501e+02 2.824000e+02 +3 2182 7.596899e+02 3.878400e+02 +1 2183 7.166499e+02 2.836699e+02 +3 2183 7.166899e+02 3.896000e+02 +1 2184 8.505400e+02 2.934800e+02 +2 2184 6.794600e+02 1.813800e+02 +3 2184 8.913600e+02 4.025400e+02 +17 2184 -1.075040e+03 6.054399e+02 +1 2185 7.714600e+02 3.325500e+02 +3 2185 7.747600e+02 4.387600e+02 +1 2186 -8.252500e+02 3.447300e+02 +3 2186 -8.186100e+02 4.789500e+02 +1 2187 9.737300e+02 3.820701e+02 +2 2187 7.512100e+02 2.236500e+02 +3 2187 1.033460e+03 4.962200e+02 +1 2188 1.178060e+03 3.833500e+02 +6 2188 9.987200e+02 2.395200e+02 +8 2188 9.761300e+02 4.457300e+02 +1 2189 1.178060e+03 3.833500e+02 +6 2189 9.987200e+02 2.395200e+02 +8 2189 9.761300e+02 4.457300e+02 +10 2189 3.933999e+02 -3.138300e+02 +17 2189 -7.882600e+02 6.497200e+02 +1 2190 1.347710e+03 3.869000e+02 +7 2190 1.037820e+03 4.229800e+02 +10 2190 4.452700e+02 -3.121000e+02 +13 2190 1.358100e+03 7.638400e+02 +17 2190 -6.506700e+02 6.470801e+02 +1 2191 -1.158330e+03 3.961400e+02 +2 2191 -3.818200e+02 1.930900e+02 +8 2191 -9.113400e+02 3.868700e+02 +1 2192 -4.521000e+02 4.027100e+02 +3 2192 -5.131700e+02 5.168000e+02 +6 2192 -1.199700e+02 2.483000e+02 +1 2193 -1.304100e+03 4.103201e+02 +2 2193 -4.506200e+02 1.953700e+02 +11 2193 2.056400e+02 2.162600e+02 +1 2194 -1.174310e+03 4.110400e+02 +2 2194 -3.889900e+02 1.999000e+02 +7 2194 1.704100e+02 3.995000e+02 +9 2194 -4.045100e+02 2.869299e+02 +10 2194 -3.036700e+02 -3.325900e+02 +11 2194 2.504301e+02 2.216400e+02 +1 2195 -1.251840e+03 4.139399e+02 +2 2195 -4.258200e+02 1.989300e+02 +11 2195 2.235800e+02 2.198300e+02 +1 2196 1.329520e+03 4.201000e+02 +7 2196 1.033930e+03 4.361899e+02 +1 2197 -1.008710e+03 4.366400e+02 +2 2197 -3.181400e+02 2.243100e+02 +7 2197 2.179700e+02 4.148000e+02 +11 2197 3.031500e+02 2.419600e+02 +1 2198 -6.364400e+02 4.745901e+02 +8 2198 -3.609900e+02 5.188300e+02 +1 2199 6.804500e+02 4.846799e+02 +6 2199 7.162100e+02 2.925100e+02 +1 2200 -1.085590e+03 5.000800e+02 +3 2200 -1.067480e+03 6.599399e+02 +1 2201 1.124300e+03 5.031200e+02 +3 2201 9.537400e+02 5.867600e+02 +1 2202 -8.837300e+02 5.315900e+02 +6 2202 -4.850400e+02 3.551600e+02 +1 2203 -1.145150e+03 5.622700e+02 +6 2203 -6.798300e+02 3.809399e+02 +1 2204 -1.152860e+03 5.742200e+02 +2 2204 -3.863200e+02 2.930700e+02 +9 2204 -4.032600e+02 3.592200e+02 +11 2204 2.520500e+02 2.904800e+02 +1 2205 -1.076350e+03 5.833700e+02 +3 2205 -1.062500e+03 7.493900e+02 +1 2206 -1.086520e+03 5.853500e+02 +8 2206 -8.557300e+02 5.334600e+02 +1 2207 -8.209600e+02 6.010000e+02 +6 2207 -4.345700e+02 4.008800e+02 +1 2208 -1.180410e+03 6.019299e+02 +6 2208 -7.041300e+02 4.085800e+02 +1 2209 -1.256470e+03 6.052500e+02 +6 2209 -7.575000e+02 4.115900e+02 +1 2210 -1.153620e+03 6.079800e+02 +2 2210 -3.844300e+02 3.108900e+02 +9 2210 -4.014500e+02 3.717700e+02 +10 2210 -3.012300e+02 -2.722300e+02 +11 2210 2.537000e+02 3.029300e+02 +12 2210 -9.302700e+02 -3.738400e+02 +18 2210 -5.232100e+02 1.166400e+02 +1 2211 -1.153620e+03 6.079800e+02 +6 2211 -6.860800e+02 4.123201e+02 +1 2212 -8.440900e+02 6.129900e+02 +2 2212 -2.617700e+02 3.426900e+02 +6 2212 -4.509700e+02 4.082600e+02 +7 2212 2.628800e+02 4.879099e+02 +10 2212 -2.271100e+02 -2.540400e+02 +11 2212 3.465000e+02 3.345900e+02 +12 2212 -8.442700e+02 -3.508600e+02 +13 2212 -1.696330e+03 1.125270e+03 +1 2213 -1.232280e+03 6.169000e+02 +7 2213 1.501600e+02 4.667400e+02 +1 2214 -1.092970e+03 6.176799e+02 +3 2214 -1.079900e+03 7.871801e+02 +9 2214 -3.813300e+02 3.797800e+02 +1 2215 -1.081550e+03 6.193900e+02 +2 2215 -3.538600e+02 3.217200e+02 +3 2215 -1.068760e+03 7.893500e+02 +5 2215 3.674100e+02 8.307400e+02 +8 2215 -8.519400e+02 5.607900e+02 +1 2216 -1.376900e+03 6.204200e+02 +6 2216 -8.415600e+02 4.240701e+02 +11 2216 1.762100e+02 2.981800e+02 +1 2217 -1.293750e+03 6.377200e+02 +2 2217 -4.528900e+02 3.219700e+02 +6 2217 -7.829700e+02 4.345800e+02 +7 2217 1.315100e+02 4.710901e+02 +11 2217 2.037100e+02 3.088300e+02 +18 2217 -5.561000e+02 1.209900e+02 +1 2218 -1.173600e+03 6.629399e+02 +2 2218 -3.961600e+02 3.404600e+02 +4 2218 8.184199e+02 4.323900e+02 +5 2218 3.354700e+02 8.362000e+02 +7 2218 1.673500e+02 4.835901e+02 +8 2218 -9.214600e+02 5.868101e+02 +9 2218 -4.107300e+02 3.942300e+02 +11 2218 2.449700e+02 3.246700e+02 +12 2218 -9.368200e+02 -3.562000e+02 +1 2219 -9.730300e+02 6.642200e+02 +2 2219 -3.065100e+02 3.539700e+02 +5 2219 4.032900e+02 8.584399e+02 +7 2219 2.266899e+02 4.933600e+02 +8 2219 -7.646100e+02 6.016400e+02 +9 2219 -3.402100e+02 4.081200e+02 +11 2219 3.116600e+02 3.386900e+02 +1 2220 -1.443110e+03 6.766600e+02 +6 2220 -8.823100e+02 4.619000e+02 +11 2220 1.480200e+02 3.202300e+02 +1 2221 -1.442220e+03 6.863101e+02 +2 2221 -5.273500e+02 3.454700e+02 +9 2221 -5.108400e+02 3.953301e+02 +1 2222 -1.388980e+03 6.919700e+02 +6 2222 -8.461000e+02 4.726600e+02 +1 2223 -1.018560e+03 7.071000e+02 +2 2223 -3.290800e+02 3.757500e+02 +7 2223 2.121400e+02 5.060500e+02 +9 2223 -3.582100e+02 4.241699e+02 +10 2223 -2.686400e+02 -2.367500e+02 +11 2223 2.948800e+02 3.539800e+02 +12 2223 -8.921400e+02 -3.335300e+02 +1 2224 -1.424830e+03 7.666400e+02 +2 2224 -5.229700e+02 3.909100e+02 +7 2224 9.056006e+01 5.112700e+02 +9 2224 -5.084301e+02 4.298500e+02 +11 2224 1.522000e+02 3.578300e+02 +1 2225 -1.424270e+03 7.788101e+02 +2 2225 -5.227900e+02 3.981400e+02 +11 2225 1.524000e+02 3.630400e+02 +1 2226 -9.965000e+02 8.376100e+02 +8 2226 -7.835900e+02 7.338400e+02 +1 2227 -1.448900e+03 8.931000e+02 +2 2227 -5.365100e+02 4.605601e+02 +7 2227 8.200000e+01 5.526400e+02 +9 2227 -5.198600e+02 4.826699e+02 +11 2227 1.421400e+02 4.082200e+02 +1 2228 -1.201600e+03 -6.117000e+02 +6 2228 -7.554800e+02 -4.189399e+02 +1 2229 -1.201600e+03 -6.117000e+02 +6 2229 -7.554800e+02 -4.189399e+02 +1 2230 -1.180470e+03 -6.104301e+02 +6 2230 -7.408200e+02 -4.188700e+02 +1 2231 -1.180470e+03 -6.104301e+02 +6 2231 -7.408200e+02 -4.188700e+02 +1 2232 -1.204100e+03 -6.045500e+02 +6 2232 -7.571000e+02 -4.136801e+02 +1 2233 -1.221790e+03 -6.046200e+02 +6 2233 -7.698700e+02 -4.131500e+02 +1 2234 -1.197930e+03 -5.986300e+02 +6 2234 -7.525300e+02 -4.099600e+02 +1 2235 -1.216110e+03 -5.985300e+02 +6 2235 -7.656200e+02 -4.092700e+02 +1 2236 -1.240410e+03 -5.937100e+02 +6 2236 -7.815500e+02 -4.048300e+02 +1 2237 -9.674100e+02 -5.659399e+02 +3 2237 -9.294600e+02 -4.901300e+02 +1 2238 -9.674100e+02 -5.659399e+02 +3 2238 -9.294600e+02 -4.901300e+02 +1 2239 1.070900e+02 -5.635300e+02 +3 2239 5.746700e+02 -4.704200e+02 +1 2240 -5.392000e+02 -5.502300e+02 +6 2240 -2.228700e+02 -4.023500e+02 +1 2241 1.018300e+02 -5.452800e+02 +6 2241 -7.976001e+01 -4.014800e+02 +1 2242 1.153101e+02 -5.383500e+02 +3 2242 5.842700e+02 -4.422000e+02 +6 2242 -7.101001e+01 -3.966801e+02 +1 2243 1.211700e+02 -5.354600e+02 +3 2243 5.911899e+02 -4.385699e+02 +6 2243 -6.646997e+01 -3.948800e+02 +1 2244 1.507100e+02 -5.312700e+02 +6 2244 -4.315997e+01 -3.922700e+02 +1 2245 1.161100e+02 -5.187500e+02 +3 2245 5.864000e+02 -4.202100e+02 +1 2246 1.565100e+02 -5.170200e+02 +3 2246 6.265900e+02 -4.190300e+02 +1 2247 1.608199e+02 -5.122300e+02 +6 2247 -3.383002e+01 -3.795200e+02 +1 2248 1.207000e+02 -4.845900e+02 +3 2248 5.889900e+02 -3.826500e+02 +1 2249 1.279700e+02 -4.820200e+02 +3 2249 5.959100e+02 -3.790100e+02 +1 2250 -3.278600e+02 -4.819301e+02 +3 2250 -4.052800e+02 -3.974399e+02 +1 2251 9.014001e+01 -4.723600e+02 +3 2251 5.505800e+02 -3.669100e+02 +6 2251 -8.310999e+01 -3.455699e+02 +1 2252 -5.732200e+02 -4.696899e+02 +6 2252 -2.516100e+02 -3.461100e+02 +1 2253 1.080000e+02 -4.687200e+02 +3 2253 5.736200e+02 -3.649500e+02 +1 2254 -9.956100e+02 -4.621700e+02 +6 2254 -5.992800e+02 -3.232800e+02 +1 2255 -9.956100e+02 -4.621700e+02 +6 2255 -5.992800e+02 -3.232800e+02 +1 2256 -1.016660e+03 -4.621600e+02 +6 2256 -6.162700e+02 -3.223200e+02 +1 2257 -1.016660e+03 -4.621600e+02 +6 2257 -6.162700e+02 -3.223200e+02 +1 2258 -1.031320e+03 -4.621400e+02 +6 2258 -6.270400e+02 -3.218100e+02 +1 2259 -1.031320e+03 -4.621400e+02 +6 2259 -6.270400e+02 -3.218100e+02 +1 2260 7.705901e+02 -4.589900e+02 +3 2260 7.752300e+02 -3.621899e+02 +6 2260 7.024200e+02 -3.786500e+02 +1 2261 7.867300e+02 -4.580100e+02 +3 2261 7.918800e+02 -3.616801e+02 +1 2262 -5.732500e+02 -4.528400e+02 +6 2262 -2.510000e+02 -3.336300e+02 +1 2263 -8.166800e+02 -4.392800e+02 +3 2263 -7.969600e+02 -3.553400e+02 +1 2264 -8.342000e+02 -4.379301e+02 +3 2264 -8.133800e+02 -3.534900e+02 +1 2265 -9.676500e+02 -4.368101e+02 +6 2265 -5.770300e+02 -3.069300e+02 +1 2266 -1.379270e+03 -4.311600e+02 +6 2266 -8.738400e+02 -2.898400e+02 +1 2267 1.511100e+02 -4.302100e+02 +3 2267 6.203101e+02 -3.223700e+02 +1 2268 -1.053760e+03 -4.271000e+02 +3 2268 -1.017550e+03 -3.434500e+02 +1 2269 -4.220601e+02 -4.244900e+02 +6 2269 -1.188300e+02 -3.209500e+02 +1 2270 1.301500e+02 -4.079000e+02 +6 2270 -5.558002e+01 -2.989900e+02 +1 2271 1.062600e+02 -4.087700e+02 +3 2271 5.727000e+02 -2.989700e+02 +1 2272 -2.873900e+02 -3.799700e+02 +6 2272 5.131995e+01 -3.016900e+02 +1 2273 9.013401e+02 -3.673000e+02 +2 2273 7.053101e+02 -2.003800e+02 +3 2273 9.505400e+02 -2.674000e+02 +1 2274 -4.301801e+02 -3.649900e+02 +3 2274 -4.794000e+02 -2.778400e+02 +1 2275 1.032700e+02 -3.588000e+02 +3 2275 5.709800e+02 -2.425100e+02 +6 2275 -7.454999e+01 -2.613800e+02 +1 2276 1.032700e+02 -3.588000e+02 +3 2276 5.709800e+02 -2.425100e+02 +1 2277 8.354004e+01 -3.591500e+02 +3 2277 5.472800e+02 -2.430601e+02 +1 2278 1.656801e+02 -3.577500e+02 +6 2278 -2.665002e+01 -2.623600e+02 +1 2279 1.289800e+02 -3.577000e+02 +3 2279 6.007000e+02 -2.410699e+02 +6 2279 -5.571997e+01 -2.612200e+02 +1 2280 1.155200e+02 -3.581200e+02 +3 2280 5.854301e+02 -2.414200e+02 +6 2280 -6.590997e+01 -2.612000e+02 +1 2281 1.046920e+03 -3.568400e+02 +6 2281 8.827800e+02 -3.092500e+02 +1 2282 7.813601e+02 -3.149200e+02 +2 2282 6.323400e+02 -1.638000e+02 +1 2283 -5.717900e+02 -3.110300e+02 +6 2283 -2.460600e+02 -2.344000e+02 +1 2284 8.568601e+02 -3.045000e+02 +6 2284 7.471000e+02 -2.658300e+02 +1 2285 -1.237340e+03 -3.024301e+02 +2 2285 -4.079000e+02 -1.863800e+02 +1 2286 -1.175880e+03 -2.966100e+02 +2 2286 -3.795200e+02 -1.822000e+02 +6 2286 -7.298400e+02 -2.037500e+02 +9 2286 -3.936600e+02 -2.219971e+00 +11 2286 2.595300e+02 -5.642999e+01 +1 2287 -1.175880e+03 -2.966100e+02 +2 2287 -3.795200e+02 -1.822000e+02 +11 2287 2.595300e+02 -5.642999e+01 +1 2288 1.445650e+03 -2.908400e+02 +7 2288 1.059090e+03 1.777300e+02 +9 2288 6.792200e+02 2.490002e+01 +12 2288 -7.912000e+01 -6.608101e+02 +17 2288 -5.886000e+02 8.246997e+01 +1 2289 1.411350e+03 -2.908900e+02 +7 2289 1.047210e+03 1.778301e+02 +1 2290 -1.520300e+02 -2.769200e+02 +3 2290 -2.971200e+02 -1.930900e+02 +1 2291 7.698301e+02 -2.701100e+02 +2 2291 6.248199e+02 -1.355800e+02 +3 2291 7.736899e+02 -1.712700e+02 +6 2291 7.057700e+02 -2.395300e+02 +1 2292 7.854099e+02 -2.670200e+02 +2 2292 6.342000e+02 -1.342000e+02 +3 2292 7.902400e+02 -1.689500e+02 +1 2293 -1.298800e+02 -2.551300e+02 +6 2293 1.660699e+02 -2.194500e+02 +8 2293 2.465601e+02 -7.375000e+01 +13 2293 -9.749900e+02 3.901001e+01 +1 2294 -1.298800e+02 -2.551300e+02 +3 2294 -2.871500e+02 -1.713500e+02 +4 2294 1.274350e+03 2.393800e+02 +5 2294 9.674299e+02 6.467700e+02 +6 2294 1.660699e+02 -2.194500e+02 +8 2294 2.465601e+02 -7.375000e+01 +9 2294 -9.672998e+01 1.143199e+02 +13 2294 -9.749900e+02 3.901001e+01 +1 2295 9.631299e+02 -2.468000e+02 +3 2295 1.016610e+03 -1.448600e+02 +6 2295 8.260900e+02 -2.268500e+02 +1 2296 -3.399301e+02 -2.415200e+02 +3 2296 -4.191400e+02 -1.523700e+02 +1 2297 5.486599e+02 -2.240300e+02 +2 2297 4.425500e+02 -6.431000e+01 +1 2298 3.355200e+02 -2.145500e+02 +2 2298 5.525000e+01 7.959998e+01 +9 2298 1.291500e+02 3.303700e+02 +11 2298 6.960601e+02 2.596000e+02 +13 2298 -1.925000e+02 3.930200e+02 +1 2299 9.166399e+02 -1.954100e+02 +2 2299 7.146700e+02 -1.025100e+02 +3 2299 9.663601e+02 -9.408002e+01 +6 2299 7.941300e+02 -1.868100e+02 +17 2299 -1.020050e+03 1.715300e+02 +1 2300 -4.418400e+02 -1.961200e+02 +6 2300 -1.272000e+02 -1.626900e+02 +1 2301 -5.448000e+02 -1.962100e+02 +6 2301 -2.200800e+02 -1.583500e+02 +1 2302 -5.396000e+02 -1.904200e+02 +6 2302 -2.140800e+02 -1.537300e+02 +1 2303 -1.295900e+02 -1.674800e+02 +2 2303 -6.841998e+01 -1.367999e+01 +3 2303 -2.874300e+02 -8.366998e+01 +5 2303 9.629299e+02 6.897100e+02 +8 2303 2.466100e+02 5.340027e+00 +9 2303 -9.739001e+01 1.680000e+02 +10 2303 -6.089001e+01 -4.452600e+02 +11 2303 5.215100e+02 1.058100e+02 +12 2303 -6.338100e+02 -5.410300e+02 +13 2303 -9.734600e+02 2.033301e+02 +16 2303 6.956300e+02 3.002600e+02 +18 2303 -3.252800e+02 -1.555005e+01 +1 2304 6.935601e+02 -1.637100e+02 +2 2304 5.747000e+02 -6.435999e+01 +17 2304 -1.257070e+03 2.323900e+02 +1 2305 -1.320996e+01 -1.564500e+02 +6 2305 3.404500e+02 -1.645300e+02 +1 2306 2.873199e+02 -1.507200e+02 +2 2306 4.570007e+00 1.470100e+02 +3 2306 -7.164001e+01 -8.376001e+01 +6 2306 5.829800e+02 -1.709400e+02 +13 2306 -3.211400e+02 5.726300e+02 +1 2307 -1.546200e+02 -1.505699e+02 +3 2307 -3.100700e+02 -6.373999e+01 +1 2308 -5.512800e+02 -1.406600e+02 +3 2308 -5.770000e+02 -4.378998e+01 +6 2308 -2.232900e+02 -1.192100e+02 +1 2309 -1.618600e+02 -1.387400e+02 +3 2309 -3.143800e+02 -5.459003e+01 +13 2309 -1.022930e+03 2.515100e+02 +1 2310 7.205701e+02 -1.186801e+02 +2 2310 5.962500e+02 -4.544000e+01 +3 2310 7.244301e+02 -1.945001e+01 +1 2311 3.261500e+02 -1.153300e+02 +2 2311 4.444000e+01 1.846000e+02 +3 2311 -3.469995e+01 -4.983002e+01 +10 2311 1.119800e+02 -3.232900e+02 +13 2311 -2.132900e+02 6.686300e+02 +1 2312 9.159099e+02 -1.103900e+02 +2 2312 7.144399e+02 -5.527002e+01 +3 2312 9.657000e+02 -7.289978e+00 +6 2312 7.954399e+02 -1.246700e+02 +7 2312 8.831499e+02 2.468201e+02 +17 2312 -1.020120e+03 2.436300e+02 +1 2313 7.655000e+02 -1.102200e+02 +2 2313 6.230100e+02 -4.097998e+01 +3 2313 7.699600e+02 -1.057001e+01 +6 2313 7.064900e+02 -1.245100e+02 +17 2313 -1.172480e+03 2.674299e+02 +1 2314 9.722300e+02 -1.078199e+02 +3 2314 1.030020e+03 -5.260010e+00 +17 2314 -9.690600e+02 2.410000e+02 +1 2315 -6.547400e+02 -1.022400e+02 +6 2315 -3.059400e+02 -8.960999e+01 +1 2316 8.225200e+02 -9.826001e+01 +2 2316 6.596000e+02 -4.221002e+01 +3 2316 8.507600e+02 2.469971e+00 +17 2316 -1.109800e+03 2.650701e+02 +1 2317 -5.263000e+01 -9.642004e+01 +8 2317 6.008000e+02 1.033100e+02 +1 2318 8.566201e+02 -8.956995e+01 +2 2318 6.814200e+02 -4.067999e+01 +3 2318 8.992200e+02 1.276001e+01 +17 2318 -1.072500e+03 2.666599e+02 +1 2319 -5.192800e+02 -8.684998e+01 +3 2319 -5.539800e+02 1.103998e+01 +1 2320 8.906599e+02 -8.538000e+01 +3 2320 9.381799e+02 1.784003e+01 +1 2321 8.997500e+02 -8.278003e+01 +2 2321 7.061400e+02 -3.895001e+01 +3 2321 9.458899e+02 2.058002e+01 +1 2322 -3.516899e+02 -8.319995e+01 +3 2322 -4.270900e+02 1.019000e+01 +1 2323 -5.571000e+02 -6.730005e+01 +3 2323 -5.812700e+02 3.341998e+01 +7 2323 3.522900e+02 2.699299e+02 +1 2324 8.447500e+02 -6.358997e+01 +2 2324 6.738800e+02 -2.456000e+01 +3 2324 8.846600e+02 4.008002e+01 +1 2325 -5.320996e+01 -4.916003e+01 +6 2325 3.158300e+02 -9.125000e+01 +8 2325 5.999600e+02 1.513300e+02 +16 2325 7.943800e+02 4.055800e+02 +1 2326 -1.151250e+03 -3.800000e+01 +2 2326 -3.700600e+02 -4.402002e+01 +9 2326 -3.875500e+02 1.023000e+02 +1 2327 7.808101e+02 -3.018994e+01 +3 2327 7.865601e+02 7.071002e+01 +17 2327 -1.157590e+03 3.405400e+02 +1 2328 -9.792800e+02 -2.821997e+01 +2 2328 -3.057400e+02 -2.984003e+01 +3 2328 -9.549500e+02 8.459003e+01 +11 2328 3.136600e+02 5.634998e+01 +1 2329 -1.022970e+03 -2.309998e+01 +2 2329 -3.191900e+02 -2.983002e+01 +3 2329 -9.941200e+02 9.303998e+01 +10 2329 -2.626100e+02 -4.558300e+02 +12 2329 -8.935200e+02 -5.768800e+02 +18 2329 -4.908900e+02 -4.285999e+01 +20 2329 -4.170000e+02 -2.356000e+02 +1 2330 8.939500e+02 -1.671997e+01 +3 2330 9.422800e+02 8.847998e+01 +17 2330 -1.037630e+03 3.277700e+02 +1 2331 -7.466600e+02 -1.609003e+01 +6 2331 -3.867600e+02 -2.546002e+01 +1 2332 7.640601e+02 -1.421002e+01 +2 2332 6.227200e+02 1.678003e+01 +3 2332 7.678199e+02 8.742999e+01 +6 2332 7.073900e+02 -5.390997e+01 +17 2332 -1.173500e+03 3.561500e+02 +1 2333 -1.265900e+02 1.359985e+00 +3 2333 -3.185800e+02 8.117999e+01 +1 2334 -1.265900e+02 1.359985e+00 +3 2334 -3.185800e+02 8.117999e+01 +1 2335 -6.579300e+02 2.460022e+00 +6 2335 -3.058100e+02 -1.713000e+01 +1 2336 9.675601e+02 1.221997e+01 +3 2336 1.025330e+03 1.183800e+02 +1 2337 -1.484890e+03 1.203998e+01 +2 2337 -5.348400e+02 -2.213000e+01 +9 2337 -5.136000e+02 1.162800e+02 +11 2337 1.460400e+02 5.759998e+01 +1 2338 -9.295996e+01 1.565002e+01 +3 2338 -2.841100e+02 9.627002e+01 +5 2338 1.017490e+03 8.060800e+02 +6 2338 2.198199e+02 -3.673999e+01 +9 2338 -1.003000e+02 3.091899e+02 +11 2338 5.137700e+02 2.415900e+02 +13 2338 -9.563400e+02 6.056799e+02 +1 2339 -7.939100e+02 1.977002e+01 +3 2339 -7.875500e+02 1.303700e+02 +1 2340 6.896899e+02 2.444995e+01 +2 2340 5.730601e+02 5.223999e+01 +3 2340 6.670300e+02 1.223500e+02 +17 2340 -1.259350e+03 4.124700e+02 +1 2341 -1.541000e+02 2.660999e+01 +6 2341 1.783000e+02 -2.926001e+01 +1 2342 8.418501e+02 4.046997e+01 +2 2342 6.728700e+02 3.971997e+01 +1 2343 -9.702002e+01 4.001001e+01 +6 2343 2.174100e+02 -2.072998e+01 +1 2344 -9.702002e+01 4.001001e+01 +6 2344 2.174100e+02 -2.072998e+01 +8 2344 3.394700e+02 2.072300e+02 +9 2344 -1.039500e+02 3.260500e+02 +13 2344 -9.650400e+02 6.586500e+02 +18 2344 -3.251400e+02 8.305005e+01 +1 2345 9.665400e+02 4.468994e+01 +2 2345 7.443800e+02 3.106000e+01 +3 2345 1.024540e+03 1.504900e+02 +1 2346 5.958101e+02 5.358008e+01 +3 2346 4.782000e+02 1.410700e+02 +1 2347 5.958101e+02 5.358008e+01 +3 2347 4.782000e+02 1.410700e+02 +1 2348 7.926599e+02 5.622998e+01 +2 2348 6.402400e+02 5.653003e+01 +17 2348 -1.143970e+03 4.166799e+02 +1 2349 -8.165700e+02 8.312000e+01 +6 2349 -4.404600e+02 4.394000e+01 +1 2350 -9.521600e+02 8.879004e+01 +2 2350 -2.935400e+02 3.563000e+01 +6 2350 -5.516300e+02 5.322998e+01 +11 2350 3.222200e+02 1.053400e+02 +12 2350 -8.751800e+02 -5.371300e+02 +1 2351 -4.888400e+02 9.057007e+01 +3 2351 -5.354800e+02 1.946400e+02 +4 2351 1.051940e+03 3.231599e+02 +5 2351 6.659500e+02 7.260400e+02 +6 2351 -1.590400e+02 3.566998e+01 +1 2352 -4.748000e+02 9.204004e+01 +6 2352 -1.460000e+02 3.634998e+01 +1 2353 -3.831000e+02 1.042300e+02 +5 2353 7.318400e+02 7.531100e+02 +6 2353 -6.456000e+01 4.103003e+01 +8 2353 -1.280000e+02 2.201900e+02 +1 2354 9.126499e+02 1.123000e+02 +2 2354 7.139301e+02 7.196002e+01 +3 2354 9.629600e+02 2.194500e+02 +6 2354 7.978800e+02 3.931000e+01 +17 2354 -1.020170e+03 4.369199e+02 +1 2355 -1.557100e+02 1.124000e+02 +6 2355 1.793101e+02 3.038000e+01 +11 2355 4.720200e+02 3.033700e+02 +13 2355 -1.080870e+03 8.043800e+02 +1 2356 9.144399e+02 1.190701e+02 +3 2356 9.651899e+02 2.264000e+02 +17 2356 -1.019460e+03 4.430601e+02 +1 2357 -5.126900e+02 1.203101e+02 +3 2357 -5.510500e+02 2.270100e+02 +9 2357 -2.055900e+02 2.329399e+02 +1 2358 9.321101e+02 1.214600e+02 +2 2358 7.255000e+02 7.651001e+01 +1 2359 8.804299e+02 1.211799e+02 +2 2359 6.961100e+02 7.945001e+01 +3 2359 9.283300e+02 2.289800e+02 +17 2359 -1.048060e+03 4.493700e+02 +1 2360 7.688201e+02 1.242900e+02 +2 2360 6.267200e+02 9.801001e+01 +3 2360 7.761100e+02 2.284000e+02 +17 2360 -1.167190e+03 4.823700e+02 +1 2361 1.172100e+03 1.422200e+02 +6 2361 9.878300e+02 6.017999e+01 +1 2362 7.736899e+02 1.467800e+02 +2 2362 6.297600e+02 1.125000e+02 +3 2362 7.794301e+02 2.486200e+02 +17 2362 -1.162120e+03 5.023101e+02 +1 2363 7.586599e+02 1.579199e+02 +2 2363 6.204000e+02 1.194800e+02 +3 2363 7.622400e+02 2.603700e+02 +17 2363 -1.177110e+03 5.146799e+02 +1 2364 -1.969500e+02 1.596799e+02 +6 2364 1.553700e+02 6.200000e+01 +8 2364 2.558300e+02 3.140800e+02 +9 2364 -1.755699e+02 4.101400e+02 +13 2364 -1.174370e+03 9.115000e+02 +1 2365 -1.020480e+03 1.609299e+02 +2 2365 -3.192300e+02 7.087000e+01 +1 2366 -1.020480e+03 1.609299e+02 +2 2366 -3.192300e+02 7.087000e+01 +1 2367 8.355000e+02 1.634500e+02 +2 2367 6.709399e+02 1.057400e+02 +3 2367 8.788900e+02 2.718600e+02 +17 2367 -1.088460e+03 4.897700e+02 +1 2368 -1.826300e+02 1.639399e+02 +6 2368 1.660400e+02 6.467999e+01 +13 2368 -1.148910e+03 9.222000e+02 +1 2369 -5.532800e+02 1.727400e+02 +3 2369 -5.833400e+02 2.843301e+02 +1 2370 8.067300e+02 1.851500e+02 +2 2370 6.521300e+02 1.276200e+02 +17 2370 -1.122130e+03 5.247500e+02 +1 2371 -1.163510e+03 1.857300e+02 +2 2371 -3.827900e+02 7.838000e+01 +1 2372 9.682900e+02 1.879600e+02 +3 2372 1.030170e+03 2.979800e+02 +8 2372 8.128700e+02 2.799299e+02 +17 2372 -9.674900e+02 4.949500e+02 +1 2373 9.842100e+02 1.900100e+02 +2 2373 7.550800e+02 1.116300e+02 +3 2373 1.047880e+03 3.000500e+02 +8 2373 8.233400e+02 2.811899e+02 +1 2374 1.389060e+03 1.939900e+02 +7 2374 1.048960e+03 3.517600e+02 +9 2374 6.617200e+02 2.335300e+02 +1 2375 7.574600e+02 2.019399e+02 +2 2375 6.187600e+02 1.468000e+02 +3 2375 7.584800e+02 3.059199e+02 +6 2375 7.079000e+02 1.014200e+02 +17 2375 -1.178150e+03 5.559700e+02 +1 2376 -5.795500e+02 2.626799e+02 +2 2376 -1.797300e+02 1.799600e+02 +9 2376 -2.267500e+02 2.874299e+02 +11 2376 4.149000e+02 2.226000e+02 +13 2376 -1.438910e+03 7.106300e+02 +1 2377 -7.500900e+02 2.632000e+02 +6 2377 -3.805600e+02 1.657400e+02 +1 2378 -5.120900e+02 2.646599e+02 +6 2378 -1.812800e+02 1.582800e+02 +1 2379 7.121299e+02 2.752000e+02 +2 2379 5.942400e+02 1.910300e+02 +3 2379 7.182300e+02 3.817900e+02 +17 2379 -1.217260e+03 6.252300e+02 +1 2380 -7.647300e+02 2.839299e+02 +3 2380 -7.671000e+02 4.122100e+02 +1 2381 -6.256400e+02 3.028101e+02 +2 2381 -1.940100e+02 1.987900e+02 +13 2381 -1.485590e+03 7.611899e+02 +1 2382 -3.934100e+02 3.052200e+02 +2 2382 -1.210500e+02 2.435300e+02 +3 2382 -4.592900e+02 4.134000e+02 +1 2383 -6.118700e+02 3.081300e+02 +3 2383 -6.363900e+02 4.280200e+02 +1 2384 -4.170500e+02 3.128000e+02 +3 2384 -4.809200e+02 4.218300e+02 +1 2385 -6.734200e+02 3.162200e+02 +2 2385 -2.085400e+02 1.991400e+02 +7 2385 3.146100e+02 4.027200e+02 +9 2385 -2.542600e+02 3.010000e+02 +10 2385 -1.895601e+02 -3.307000e+02 +13 2385 -1.533030e+03 7.644900e+02 +1 2386 -8.089000e+02 3.179600e+02 +3 2386 -8.025300e+02 4.479500e+02 +1 2387 -7.170300e+02 3.193401e+02 +6 2387 -3.554900e+02 2.040300e+02 +1 2388 6.820601e+02 3.386300e+02 +2 2388 5.493000e+02 3.046200e+02 +3 2388 5.786801e+02 4.286500e+02 +17 2388 -1.326860e+03 8.065500e+02 +1 2389 1.197200e+03 3.477000e+02 +6 2389 1.013230e+03 2.128200e+02 +1 2390 -8.355300e+02 3.485701e+02 +3 2390 -8.286700e+02 4.849600e+02 +1 2391 8.817400e+02 3.624399e+02 +2 2391 6.986700e+02 2.186600e+02 +3 2391 9.293600e+02 4.754000e+02 +8 2391 7.663300e+02 4.299700e+02 +1 2392 -9.228900e+02 3.679700e+02 +2 2392 -2.869500e+02 1.938100e+02 +3 2392 -9.073200e+02 5.092300e+02 +8 2392 -7.170000e+02 3.794600e+02 +9 2392 -3.226000e+02 2.868700e+02 +11 2392 3.271300e+02 2.218900e+02 +1 2393 -9.250100e+02 3.808101e+02 +3 2393 -9.077000e+02 5.228400e+02 +1 2394 1.015500e+03 3.958000e+02 +3 2394 1.078160e+03 5.094399e+02 +8 2394 8.532600e+02 4.561200e+02 +1 2395 -1.250250e+03 4.237900e+02 +7 2395 1.478300e+02 4.015500e+02 +1 2396 -1.366820e+03 4.312000e+02 +2 2396 -4.817600e+02 2.052900e+02 +11 2396 1.830800e+02 2.225700e+02 +1 2397 -1.489730e+03 4.341699e+02 +2 2397 -5.465200e+02 2.062400e+02 +1 2398 7.043101e+02 5.119100e+02 +6 2398 7.349500e+02 3.116700e+02 +17 2398 -1.302100e+03 9.952000e+02 +1 2399 -9.104300e+02 5.500701e+02 +3 2399 -8.992000e+02 7.061700e+02 +8 2399 -7.068900e+02 5.223900e+02 +11 2399 3.280300e+02 3.006000e+02 +1 2400 -1.141200e+03 5.934000e+02 +2 2400 -3.794200e+02 3.031800e+02 +9 2400 -3.975900e+02 3.664199e+02 +1 2401 -1.364060e+03 6.266400e+02 +6 2401 -8.321700e+02 4.282000e+02 +1 2402 -1.378860e+03 6.278300e+02 +6 2402 -8.420400e+02 4.290601e+02 +1 2403 -1.098920e+03 6.442500e+02 +2 2403 -3.622300e+02 3.345900e+02 +11 2403 2.699800e+02 3.218000e+02 +1 2404 -1.058340e+03 6.784399e+02 +2 2404 -3.426700e+02 3.548600e+02 +11 2404 2.842400e+02 3.371600e+02 +1 2405 -1.123020e+03 6.918101e+02 +2 2405 -3.711300e+02 3.580300e+02 +7 2405 1.824100e+02 4.945400e+02 +8 2405 -8.864100e+02 6.117100e+02 +10 2405 -2.939800e+02 -2.470500e+02 +11 2405 2.632800e+02 3.380100e+02 +18 2405 -5.164100e+02 1.389099e+02 +1 2406 -1.114770e+03 7.099200e+02 +8 2406 -8.800900e+02 6.263101e+02 +1 2407 -1.311580e+03 7.163300e+02 +2 2407 -4.598200e+02 3.633200e+02 +1 2408 -1.041770e+03 7.313900e+02 +8 2408 -8.186200e+02 6.491100e+02 +1 2409 -1.057600e+03 7.392400e+02 +8 2409 -8.315000e+02 6.544600e+02 +1 2410 -1.411890e+03 7.648400e+02 +2 2410 -5.162900e+02 3.909300e+02 +9 2410 -5.034700e+02 4.297000e+02 +1 2411 -1.399150e+03 7.762400e+02 +2 2411 -5.100700e+02 3.967800e+02 +1 2412 -1.416710e+03 7.845500e+02 +2 2412 -5.191500e+02 4.015200e+02 +9 2412 -5.058700e+02 4.379000e+02 +1 2413 -9.788400e+02 8.387200e+02 +6 2413 -5.517300e+02 5.667800e+02 +1 2414 -9.635200e+02 8.492100e+02 +2 2414 -3.074400e+02 4.616300e+02 +1 2415 -1.348370e+03 8.862300e+02 +2 2415 -5.011600e+02 4.684700e+02 +9 2415 -4.912600e+02 4.914900e+02 +1 2416 -1.459060e+03 8.997900e+02 +2 2416 -5.421700e+02 4.638400e+02 +11 2416 1.382600e+02 4.108101e+02 +1 2417 -1.239400e+03 9.225900e+02 +2 2417 -4.281800e+02 4.817400e+02 +7 2417 1.463000e+02 5.673900e+02 +11 2417 2.205000e+02 4.270500e+02 +1 2418 -1.194330e+03 -6.110400e+02 +6 2418 -7.507500e+02 -4.185699e+02 +1 2419 -1.222600e+03 -6.113400e+02 +6 2419 -7.704800e+02 -4.179000e+02 +1 2420 -1.222600e+03 -6.113400e+02 +6 2420 -7.704800e+02 -4.179000e+02 +1 2421 -1.187920e+03 -6.105000e+02 +6 2421 -7.463400e+02 -4.185500e+02 +1 2422 -1.187920e+03 -6.105000e+02 +6 2422 -7.463400e+02 -4.185500e+02 +1 2423 1.606700e+02 -6.069800e+02 +6 2423 -4.042999e+01 -4.506899e+02 +1 2424 -1.197570e+03 -6.061100e+02 +6 2424 -7.526100e+02 -4.151100e+02 +1 2425 -1.205060e+03 -5.971801e+02 +6 2425 -7.576300e+02 -4.088700e+02 +1 2426 -1.046000e+03 -5.683900e+02 +3 2426 -1.005530e+03 -4.933300e+02 +6 2426 -6.415000e+02 -3.943500e+02 +1 2427 -9.975400e+02 -5.653500e+02 +6 2427 -6.049000e+02 -3.941801e+02 +1 2428 1.242400e+02 -5.636400e+02 +3 2428 5.938199e+02 -4.699900e+02 +6 2428 -6.453998e+01 -4.161200e+02 +1 2429 4.227400e+02 -5.632500e+02 +3 2429 4.330500e+02 -4.704600e+02 +1 2430 1.346899e+02 -5.621000e+02 +3 2430 6.051899e+02 -4.685000e+02 +1 2431 -5.318300e+02 -5.494900e+02 +6 2431 -2.165500e+02 -4.023800e+02 +1 2432 -5.318300e+02 -5.494900e+02 +6 2432 -2.165500e+02 -4.023800e+02 +1 2433 7.733501e+02 -5.456000e+02 +3 2433 7.782100e+02 -4.487500e+02 +6 2433 7.031200e+02 -4.420400e+02 +1 2434 7.741699e+02 -5.383400e+02 +3 2434 7.781500e+02 -4.414500e+02 +6 2434 7.034100e+02 -4.365900e+02 +1 2435 7.751699e+02 -5.286801e+02 +6 2435 7.045500e+02 -4.288700e+02 +1 2436 1.375900e+02 -5.290100e+02 +3 2436 6.081600e+02 -4.313300e+02 +1 2437 1.145699e+02 -5.249100e+02 +3 2437 5.871400e+02 -4.277900e+02 +6 2437 -7.215002e+01 -3.866300e+02 +1 2438 1.279000e+02 -5.241700e+02 +3 2438 5.985699e+02 -4.261600e+02 +1 2439 -1.073710e+03 -5.217400e+02 +3 2439 -1.025650e+03 -4.440200e+02 +6 2439 -6.690200e+02 -3.608199e+02 +1 2440 8.905005e+01 -4.826400e+02 +3 2440 5.481000e+02 -3.797700e+02 +6 2440 -8.387000e+01 -3.554399e+02 +1 2441 9.290500e+02 -4.751700e+02 +2 2441 7.204100e+02 -2.615300e+02 +1 2442 8.412900e+02 -4.710000e+02 +3 2442 8.711600e+02 -3.730100e+02 +1 2443 8.412900e+02 -4.710000e+02 +2 2443 6.688199e+02 -2.569300e+02 +3 2443 8.711600e+02 -3.730100e+02 +1 2444 9.217700e+02 -4.695900e+02 +3 2444 9.710200e+02 -3.705800e+02 +1 2445 7.738401e+02 -4.649900e+02 +6 2445 7.048400e+02 -3.836500e+02 +1 2446 -8.112800e+02 -4.436300e+02 +3 2446 -7.926500e+02 -3.594399e+02 +1 2447 -8.478700e+02 -4.434600e+02 +3 2447 -8.242500e+02 -3.595200e+02 +1 2448 -1.034970e+03 -4.373500e+02 +6 2448 -6.289600e+02 -3.049100e+02 +1 2449 -1.292300e+02 -4.277800e+02 +3 2449 -2.837300e+02 -3.432000e+02 +1 2450 1.087200e+02 -4.186000e+02 +3 2450 5.757600e+02 -3.095400e+02 +1 2451 -7.849800e+02 -4.138900e+02 +3 2451 -7.668500e+02 -3.277600e+02 +6 2451 -4.304200e+02 -2.977600e+02 +1 2452 1.353000e+02 -4.121100e+02 +3 2452 6.050900e+02 -3.021400e+02 +1 2453 -5.351000e+02 -4.080900e+02 +3 2453 -5.630700e+02 -3.222800e+02 +1 2454 1.120699e+02 -4.069301e+02 +3 2454 5.812200e+02 -2.965200e+02 +6 2454 -6.747998e+01 -2.981500e+02 +1 2455 -4.460200e+02 -4.056600e+02 +6 2455 -1.358800e+02 -3.064500e+02 +1 2456 -9.267600e+02 -3.955300e+02 +3 2456 -8.939700e+02 -3.086400e+02 +1 2457 -4.390100e+02 -3.777500e+02 +6 2457 -1.300500e+02 -2.874600e+02 +1 2458 1.802800e+02 -3.634900e+02 +3 2458 6.466899e+02 -2.480699e+02 +6 2458 -1.296997e+01 -2.675800e+02 +1 2459 -4.542000e+02 -3.641600e+02 +2 2459 -1.394400e+02 -1.902100e+02 +9 2459 -1.868000e+02 6.530029e+00 +1 2460 9.298501e+02 -3.601300e+02 +3 2460 9.829700e+02 -2.598600e+02 +1 2461 9.037900e+02 -3.603500e+02 +2 2461 7.059900e+02 -1.964000e+02 +3 2461 9.532800e+02 -2.606300e+02 +1 2462 -1.077200e+02 -3.594500e+02 +2 2462 -5.687000e+01 -1.550500e+02 +3 2462 -2.678500e+02 -2.751500e+02 +8 2462 2.752400e+02 -1.655500e+02 +9 2462 -8.571997e+01 5.319995e+01 +1 2463 -1.077200e+02 -3.594500e+02 +2 2463 -5.687000e+01 -1.550500e+02 +3 2463 -2.678500e+02 -2.751500e+02 +9 2463 -8.571997e+01 5.319995e+01 +1 2464 1.553101e+02 -3.588000e+02 +6 2464 -3.560999e+01 -2.628500e+02 +1 2465 -4.610300e+02 -3.594600e+02 +6 2465 -1.460500e+02 -2.746200e+02 +1 2466 1.095280e+03 -3.562600e+02 +6 2466 9.195200e+02 -3.098900e+02 +1 2467 -1.191003e+01 -3.563000e+02 +8 2467 6.357300e+02 -1.532600e+02 +1 2468 -1.299200e+02 -3.469200e+02 +3 2468 -2.862300e+02 -2.626300e+02 +1 2469 -1.377080e+03 -3.359700e+02 +6 2469 -8.716400e+02 -2.244300e+02 +1 2470 -1.359200e+02 -3.349900e+02 +6 2470 1.587100e+02 -2.729500e+02 +1 2471 -3.408000e+02 -3.239301e+02 +3 2471 -4.185600e+02 -2.356000e+02 +1 2472 1.039130e+03 -3.136000e+02 +3 2472 1.104680e+03 -2.117400e+02 +6 2472 8.757900e+02 -2.764600e+02 +8 2472 8.554100e+02 -1.413600e+02 +1 2473 -1.177900e+02 -3.117900e+02 +8 2473 2.638400e+02 -1.225000e+02 +1 2474 -1.082770e+03 -2.936700e+02 +6 2474 -6.621900e+02 -2.041300e+02 +1 2475 -1.277000e+03 -2.899500e+02 +6 2475 -8.002600e+02 -1.952500e+02 +1 2476 -7.909400e+02 -2.891100e+02 +3 2476 -7.773500e+02 -1.960699e+02 +1 2477 -1.949951e+00 -2.862900e+02 +6 2477 3.440699e+02 -2.512900e+02 +1 2478 -9.279200e+02 -2.823400e+02 +3 2478 -8.971300e+02 -1.876100e+02 +1 2479 -1.085090e+03 -2.790100e+02 +6 2479 -6.638600e+02 -1.940600e+02 +1 2480 -1.085090e+03 -2.790100e+02 +6 2480 -6.638600e+02 -1.940600e+02 +1 2481 8.899800e+02 -2.771500e+02 +6 2481 7.724399e+02 -2.462500e+02 +1 2482 9.026001e+02 -2.722500e+02 +2 2482 7.062100e+02 -1.466900e+02 +3 2482 9.503601e+02 -1.717900e+02 +8 2482 7.736200e+02 -1.059700e+02 +1 2483 -1.096920e+03 -2.692000e+02 +2 2483 -3.442600e+02 -1.660200e+02 +1 2484 -1.126910e+03 -2.638700e+02 +2 2484 -3.568900e+02 -1.643400e+02 +3 2484 -1.091920e+03 -1.685100e+02 +6 2484 -6.939600e+02 -1.825100e+02 +11 2484 2.757600e+02 -4.312000e+01 +1 2485 -1.126910e+03 -2.638700e+02 +6 2485 -6.939600e+02 -1.825100e+02 +1 2486 1.033850e+03 -2.538600e+02 +3 2486 1.097600e+03 -1.510800e+02 +1 2487 1.039030e+03 -2.531899e+02 +3 2487 1.103470e+03 -1.508600e+02 +1 2488 9.515901e+02 -2.478400e+02 +3 2488 1.002010e+03 -1.458300e+02 +1 2489 -3.449700e+02 -2.372800e+02 +8 2489 -8.283002e+01 -6.820001e+01 +1 2490 6.088301e+02 -2.181200e+02 +2 2490 4.959100e+02 -7.119000e+01 +3 2490 5.026700e+02 -1.272800e+02 +11 2490 9.736899e+02 5.534998e+01 +17 2490 -1.411510e+03 2.247800e+02 +1 2491 3.186899e+02 -2.077000e+02 +2 2491 3.713000e+01 8.666998e+01 +3 2491 -4.123999e+01 -1.379900e+02 +11 2491 6.800200e+02 2.660900e+02 +13 2491 -2.383000e+02 4.137100e+02 +1 2492 4.747600e+02 -2.029900e+02 +3 2492 2.398500e+02 -1.227600e+02 +1 2493 -4.318500e+02 -1.982400e+02 +5 2493 7.144900e+02 6.167200e+02 +6 2493 -1.169200e+02 -1.646000e+02 +8 2493 -1.919100e+02 -3.798999e+01 +1 2494 -5.524300e+02 -1.943101e+02 +6 2494 -2.256800e+02 -1.561500e+02 +1 2495 -2.827000e+02 -1.754100e+02 +3 2495 -3.827500e+02 -8.963000e+01 +1 2496 5.458501e+02 -1.701899e+02 +2 2496 4.413000e+02 -2.857001e+01 +3 2496 4.108500e+02 -8.284998e+01 +11 2496 9.361200e+02 9.363000e+01 +17 2496 -1.512420e+03 2.927000e+02 +1 2497 3.466200e+02 -1.624600e+02 +2 2497 6.565002e+01 1.355200e+02 +3 2497 -1.509998e+01 -9.533002e+01 +11 2497 7.069200e+02 3.106000e+02 +13 2497 -1.613900e+02 5.381500e+02 +20 2497 -1.345800e+02 -9.800000e+01 +1 2498 -6.661600e+02 -1.596000e+02 +6 2498 -3.179900e+02 -1.296200e+02 +1 2499 -2.719995e+01 -1.567600e+02 +6 2499 3.310800e+02 -1.639400e+02 +8 2499 6.268400e+02 4.397998e+01 +1 2500 3.330601e+02 -1.396200e+02 +2 2500 5.184998e+01 1.590600e+02 +3 2500 -2.831006e+01 -7.284998e+01 +10 2500 1.163800e+02 -3.380300e+02 +11 2500 6.940400e+02 3.323000e+02 +13 2500 -1.962800e+02 6.013800e+02 +20 2500 -1.414301e+02 -8.564001e+01 +1 2501 5.368199e+02 -1.222400e+02 +2 2501 4.274301e+02 1.300000e+01 +3 2501 3.848300e+02 -3.807001e+01 +17 2501 -1.544220e+03 3.586899e+02 +1 2502 2.984000e+02 -1.150800e+02 +2 2502 1.615002e+01 1.853300e+02 +3 2502 -6.109998e+01 -4.945001e+01 +11 2502 6.609000e+02 3.551600e+02 +1 2503 -2.758997e+01 -1.131400e+02 +8 2503 6.264000e+02 8.684998e+01 +1 2504 -2.308997e+01 -1.082700e+02 +8 2504 6.308500e+02 9.162000e+01 +1 2505 -2.308997e+01 -1.082700e+02 +8 2505 6.308500e+02 9.162000e+01 +1 2506 2.958700e+02 -1.025000e+02 +2 2506 1.404999e+01 1.981400e+02 +3 2506 -6.246997e+01 -3.742999e+01 +10 2506 9.456995e+01 -3.156899e+02 +11 2506 6.594700e+02 3.666200e+02 +12 2506 -3.698600e+02 -3.308000e+02 +13 2506 -2.926100e+02 7.046899e+02 +1 2507 -6.275500e+02 -1.030100e+02 +6 2507 -3.379800e+02 -7.978998e+01 +1 2508 7.630500e+02 -1.023300e+02 +2 2508 6.218700e+02 -3.663000e+01 +3 2508 7.678400e+02 -2.840027e+00 +6 2508 7.054700e+02 -1.184700e+02 +17 2508 -1.174590e+03 2.747300e+02 +1 2509 6.881699e+02 -9.981006e+01 +3 2509 6.601000e+02 -5.960022e+00 +17 2509 -1.265410e+03 2.933101e+02 +1 2510 6.833401e+02 -9.667004e+01 +2 2510 5.666899e+02 -2.066998e+01 +3 2510 6.529600e+02 2.100220e-01 +1 2511 8.500100e+02 -7.979004e+01 +3 2511 8.927200e+02 2.321002e+01 +1 2512 1.206910e+03 -7.314001e+01 +6 2512 8.658101e+02 -7.933002e+01 +1 2513 9.057700e+02 -7.181006e+01 +3 2513 9.566799e+02 3.215997e+01 +17 2513 -1.029680e+03 2.770000e+02 +1 2514 7.212600e+02 -6.596997e+01 +2 2514 5.960000e+02 -1.466998e+01 +1 2515 9.060200e+02 -5.979004e+01 +3 2515 9.573301e+02 4.410999e+01 +1 2516 1.098520e+03 -5.694995e+01 +8 2516 9.101100e+02 7.344000e+01 +1 2517 1.105670e+03 -5.651001e+01 +6 2517 9.325601e+02 -8.701001e+01 +8 2517 9.159100e+02 7.409003e+01 +1 2518 -8.431500e+02 -5.088000e+01 +6 2518 -4.638000e+02 -4.696002e+01 +1 2519 9.301001e+02 -4.246997e+01 +2 2519 7.233900e+02 -1.759003e+01 +3 2519 9.853201e+02 6.250000e+01 +6 2519 8.055400e+02 -7.442999e+01 +1 2520 1.119730e+03 -2.877002e+01 +6 2520 9.440800e+02 -6.678003e+01 +8 2520 9.237100e+02 9.759998e+01 +17 2520 -8.438000e+02 3.032900e+02 +1 2521 -1.299900e+02 -2.900000e+01 +6 2521 1.936899e+02 -6.703003e+01 +8 2521 3.081700e+02 1.402600e+02 +1 2522 1.110990e+03 -2.779004e+01 +6 2522 9.377800e+02 -6.603003e+01 +8 2522 9.174399e+02 9.834998e+01 +1 2523 -1.322070e+03 -2.796997e+01 +2 2523 -4.487000e+02 -4.289001e+01 +1 2524 8.460801e+02 -1.965002e+01 +2 2524 6.743400e+02 3.739990e+00 +17 2524 -1.085020e+03 3.353301e+02 +1 2525 8.460801e+02 -1.965002e+01 +2 2525 6.743400e+02 3.739990e+00 +1 2526 -5.681300e+02 -1.271002e+01 +3 2526 -5.929000e+02 9.010999e+01 +1 2527 -8.859998e+01 -4.640015e+00 +3 2527 -2.794900e+02 7.526001e+01 +1 2528 -1.115090e+03 8.969971e+00 +2 2528 -3.572400e+02 -1.671002e+01 +3 2528 -1.088060e+03 1.257700e+02 +1 2529 -7.131600e+02 2.202002e+01 +6 2529 -3.520100e+02 -1.119995e+00 +1 2530 9.310701e+02 2.342993e+01 +6 2530 8.104600e+02 -2.526001e+01 +1 2531 -2.068300e+02 2.445996e+01 +8 2531 2.384399e+02 1.879500e+02 +1 2532 -5.731500e+02 3.466992e+01 +2 2532 -1.738900e+02 4.315002e+01 +9 2532 -2.217900e+02 1.827600e+02 +1 2533 -1.050601e+02 4.159009e+01 +3 2533 -2.973300e+02 1.210700e+02 +11 2533 5.046100e+02 2.587600e+02 +13 2533 -9.827700e+02 6.593000e+02 +1 2534 7.057600e+02 4.317993e+01 +2 2534 5.863101e+02 5.589001e+01 +17 2534 -1.233070e+03 4.182700e+02 +1 2535 -4.230000e+02 4.260999e+01 +4 2535 1.083440e+03 3.137400e+02 +5 2535 7.098800e+02 7.184399e+02 +6 2535 -1.015000e+02 -6.699829e-01 +8 2535 -1.775300e+02 1.617700e+02 +13 2535 -1.289310e+03 4.368800e+02 +1 2536 9.180500e+02 5.208008e+01 +3 2536 9.682600e+02 1.579900e+02 +1 2537 7.840901e+02 5.354004e+01 +2 2537 6.361801e+02 5.539001e+01 +3 2537 7.931700e+02 1.556400e+02 +17 2537 -1.151700e+03 4.149099e+02 +1 2538 -2.505100e+02 5.946997e+01 +3 2538 -3.691100e+02 1.492100e+02 +1 2539 9.128000e+02 6.430005e+01 +8 2539 8.865800e+02 1.894600e+02 +1 2540 8.160300e+02 6.623999e+01 +2 2540 6.571000e+02 5.532001e+01 +17 2540 -1.113450e+03 4.126699e+02 +1 2541 -2.811899e+02 6.614001e+01 +3 2541 -3.872500e+02 1.573000e+02 +1 2542 -2.955100e+02 7.150000e+01 +3 2542 -3.971900e+02 1.646500e+02 +1 2543 8.743401e+02 9.227002e+01 +2 2543 6.925000e+02 6.194000e+01 +17 2543 -1.053880e+03 4.226500e+02 +1 2544 8.132800e+02 9.684009e+01 +3 2544 8.404900e+02 2.022000e+02 +1 2545 8.680300e+02 1.125701e+02 +3 2545 9.143700e+02 2.197300e+02 +6 2545 7.655100e+02 3.944000e+01 +1 2546 1.025360e+03 1.393700e+02 +3 2546 1.088430e+03 2.476200e+02 +6 2546 8.779200e+02 5.896002e+01 +17 2546 -9.202200e+02 4.503500e+02 +1 2547 -6.490800e+02 1.395701e+02 +3 2547 -6.687600e+02 2.510200e+02 +1 2548 -2.542200e+02 1.410200e+02 +8 2548 6.659998e+01 2.699100e+02 +1 2549 1.157030e+03 1.430601e+02 +6 2549 9.766200e+02 6.033002e+01 +1 2550 1.030640e+03 1.437500e+02 +3 2550 1.093990e+03 2.523800e+02 +1 2551 -6.491600e+02 1.480100e+02 +6 2551 -2.954300e+02 8.264001e+01 +1 2552 -1.976801e+02 1.529500e+02 +6 2552 1.541700e+02 5.733002e+01 +9 2552 -1.757200e+02 4.055601e+02 +11 2552 4.403199e+02 3.345100e+02 +13 2552 -1.175380e+03 8.977400e+02 +1 2553 8.445901e+02 1.657900e+02 +3 2553 8.891400e+02 2.742500e+02 +1 2554 8.267600e+02 1.661200e+02 +3 2554 8.671700e+02 2.740100e+02 +1 2555 -6.679400e+02 1.666599e+02 +6 2555 -3.102900e+02 9.573999e+01 +1 2556 8.526299e+02 1.678201e+02 +3 2556 8.980100e+02 2.762400e+02 +1 2557 8.394500e+02 1.695300e+02 +3 2557 8.827400e+02 2.775701e+02 +1 2558 -9.553800e+02 1.755601e+02 +3 2558 -9.351400e+02 3.035400e+02 +6 2558 -5.510600e+02 1.134800e+02 +1 2559 9.080901e+02 1.792200e+02 +2 2559 7.124399e+02 1.091400e+02 +3 2559 9.640801e+02 2.887600e+02 +1 2560 9.461499e+02 1.849900e+02 +3 2560 1.005930e+03 2.948401e+02 +1 2561 9.106399e+02 1.850100e+02 +3 2561 9.674199e+02 2.942900e+02 +6 2561 7.960000e+02 9.259003e+01 +1 2562 -9.377000e+02 1.917000e+02 +3 2562 -9.187600e+02 3.196699e+02 +6 2562 -5.365200e+02 1.236800e+02 +8 2562 -7.282600e+02 2.431200e+02 +1 2563 -5.710900e+02 1.959000e+02 +3 2563 -5.987100e+02 3.090400e+02 +6 2563 -2.324500e+02 1.133100e+02 +13 2563 -1.426850e+03 6.154399e+02 +1 2564 7.727200e+02 2.103401e+02 +2 2564 6.287700e+02 1.522500e+02 +17 2564 -1.163190e+03 5.630601e+02 +1 2565 7.549600e+02 2.098600e+02 +2 2565 6.184100e+02 1.519000e+02 +3 2565 7.584700e+02 3.142700e+02 +6 2565 7.071700e+02 1.072800e+02 +17 2565 -1.179890e+03 5.636599e+02 +1 2566 7.549600e+02 2.098600e+02 +2 2566 6.184100e+02 1.519000e+02 +3 2566 7.584700e+02 3.142700e+02 +6 2566 7.071700e+02 1.072800e+02 +17 2566 -1.179890e+03 5.636599e+02 +1 2567 9.355801e+02 2.270500e+02 +6 2567 8.179700e+02 1.236300e+02 +1 2568 9.461101e+02 2.288401e+02 +2 2568 7.338800e+02 1.379500e+02 +6 2568 8.242200e+02 1.244800e+02 +1 2569 7.523000e+02 2.305000e+02 +2 2569 6.172800e+02 1.645600e+02 +3 2569 7.562500e+02 3.353600e+02 +6 2569 7.058500e+02 1.222900e+02 +17 2569 -1.182370e+03 5.830500e+02 +1 2570 -4.371200e+02 2.334299e+02 +6 2570 -1.099700e+02 1.318300e+02 +1 2571 -2.076300e+02 2.385300e+02 +6 2571 1.504700e+02 1.155200e+02 +1 2572 -5.602000e+02 2.432100e+02 +6 2572 -2.235600e+02 1.446600e+02 +1 2573 -6.861700e+02 2.445701e+02 +6 2573 -3.277900e+02 1.508100e+02 +1 2574 8.015801e+02 2.506599e+02 +2 2574 6.483300e+02 1.705100e+02 +1 2575 8.369600e+02 2.844800e+02 +3 2575 8.740601e+02 3.938201e+02 +1 2576 8.369600e+02 2.844800e+02 +3 2576 8.740601e+02 3.938201e+02 +1 2577 -6.467400e+02 2.840901e+02 +3 2577 -6.610800e+02 4.066200e+02 +1 2578 -4.050500e+02 2.973800e+02 +3 2578 -4.698500e+02 4.056400e+02 +1 2579 8.461001e+02 2.997200e+02 +2 2579 6.761200e+02 1.861900e+02 +3 2579 8.853600e+02 4.100900e+02 +6 2579 7.579500e+02 1.758700e+02 +1 2580 9.130701e+02 3.066100e+02 +2 2580 7.160100e+02 1.837700e+02 +3 2580 9.640300e+02 4.178201e+02 +6 2580 8.026500e+02 1.813200e+02 +8 2580 7.859800e+02 3.817100e+02 +17 2580 -1.017060e+03 6.070901e+02 +1 2581 -5.049300e+02 3.094700e+02 +6 2581 -1.763200e+02 1.880900e+02 +1 2582 -5.012200e+02 3.141400e+02 +6 2582 -1.733300e+02 1.920500e+02 +1 2583 -8.184600e+02 3.225601e+02 +3 2583 -8.126300e+02 4.548700e+02 +6 2583 -4.371000e+02 2.094000e+02 +1 2584 9.608000e+02 3.272100e+02 +8 2584 8.155300e+02 3.982600e+02 +17 2584 -9.737300e+02 6.190300e+02 +1 2585 9.820200e+02 3.309700e+02 +2 2585 7.550800e+02 1.936200e+02 +3 2585 1.041910e+03 4.434800e+02 +6 2585 8.508700e+02 1.997200e+02 +1 2586 -8.489300e+02 3.349199e+02 +3 2586 -8.391900e+02 4.702300e+02 +1 2587 1.157910e+03 3.463900e+02 +6 2587 9.832700e+02 2.118300e+02 +1 2588 -1.000810e+03 3.798900e+02 +2 2588 -3.179300e+02 1.939900e+02 +3 2588 -9.837100e+02 5.249900e+02 +6 2588 -5.788800e+02 2.538900e+02 +1 2589 -4.590300e+02 3.948600e+02 +2 2589 -1.504500e+02 2.925500e+02 +3 2589 -5.181300e+02 5.095500e+02 +6 2589 -1.249500e+02 2.435100e+02 +8 2589 -2.239400e+02 4.547800e+02 +11 2589 4.393199e+02 3.175900e+02 +13 2589 -1.322370e+03 9.902000e+02 +1 2590 -1.173550e+03 3.999500e+02 +8 2590 -9.226100e+02 3.888500e+02 +1 2591 8.484500e+02 4.006899e+02 +6 2591 7.612400e+02 2.495200e+02 +1 2592 -1.183530e+03 4.099099e+02 +2 2592 -3.939800e+02 1.993600e+02 +1 2593 -6.037900e+02 4.565400e+02 +3 2593 -6.740600e+02 5.740300e+02 +13 2593 -1.564200e+03 1.101470e+03 +1 2594 -6.037900e+02 4.641699e+02 +3 2594 -6.743100e+02 5.817600e+02 +6 2594 -2.182600e+02 2.913700e+02 +13 2594 -1.564270e+03 1.113780e+03 +1 2595 -6.041200e+02 4.715500e+02 +3 2595 -6.746400e+02 5.895400e+02 +9 2595 -2.752700e+02 4.272800e+02 +13 2595 -1.564380e+03 1.126120e+03 +1 2596 -6.011600e+02 4.757100e+02 +3 2596 -6.708300e+02 5.940300e+02 +9 2596 -2.737200e+02 4.300200e+02 +13 2596 -1.559210e+03 1.133840e+03 +1 2597 -1.109570e+03 4.851000e+02 +3 2597 -1.090290e+03 6.445000e+02 +1 2598 8.284800e+02 4.896400e+02 +3 2598 7.191500e+02 5.742500e+02 +6 2598 8.253700e+02 2.958600e+02 +1 2599 -1.092030e+03 4.901100e+02 +3 2599 -1.071950e+03 6.490800e+02 +1 2600 8.301101e+02 5.049900e+02 +3 2600 7.210100e+02 5.918101e+02 +1 2601 7.611699e+02 5.154399e+02 +3 2601 6.576500e+02 6.050900e+02 +8 2601 9.314800e+02 6.203500e+02 +1 2602 -1.185270e+03 5.190900e+02 +8 2602 -9.281500e+02 4.788300e+02 +1 2603 -1.106200e+03 5.344100e+02 +3 2603 -1.092290e+03 6.968800e+02 +8 2603 -8.706500e+02 4.946400e+02 +1 2604 -1.090090e+03 5.521600e+02 +2 2604 -3.552000e+02 2.834000e+02 +11 2604 2.754600e+02 2.836500e+02 +1 2605 -1.264560e+03 6.407800e+02 +6 2605 -7.637700e+02 4.362400e+02 +1 2606 -9.496000e+02 6.480800e+02 +3 2606 -9.370600e+02 8.150601e+02 +1 2607 -1.265280e+03 6.605900e+02 +6 2607 -7.623600e+02 4.496400e+02 +8 2607 -9.913900e+02 5.809100e+02 +1 2608 -1.080540e+03 6.830300e+02 +8 2608 -8.527900e+02 6.079600e+02 +11 2608 2.777200e+02 3.372600e+02 +1 2609 -1.047610e+03 7.148400e+02 +8 2609 -8.229800e+02 6.357600e+02 +1 2610 -1.098360e+03 7.150500e+02 +8 2610 -8.660100e+02 6.310701e+02 +1 2611 -1.047260e+03 7.266500e+02 +6 2611 -6.042700e+02 4.913000e+02 +8 2611 -8.228700e+02 6.455200e+02 +1 2612 -8.441300e+02 7.565200e+02 +8 2612 -6.463400e+02 6.899700e+02 +1 2613 -1.417510e+03 7.738400e+02 +2 2613 -5.191800e+02 3.950200e+02 +9 2613 -5.058199e+02 4.332400e+02 +11 2613 1.549900e+02 3.612400e+02 +1 2614 -8.202300e+02 7.762300e+02 +6 2614 -4.274300e+02 5.204600e+02 +1 2615 -8.202300e+02 7.762300e+02 +6 2615 -4.274300e+02 5.204600e+02 +1 2616 -1.411330e+03 7.770500e+02 +2 2616 -5.163600e+02 3.972900e+02 +1 2617 -1.026010e+03 7.913300e+02 +2 2617 -3.362600e+02 4.249700e+02 +11 2617 2.896200e+02 3.901700e+02 +1 2618 -1.029150e+03 8.074299e+02 +2 2618 -3.394100e+02 4.344299e+02 +11 2618 2.871100e+02 3.975000e+02 +1 2619 -1.006150e+03 8.459399e+02 +8 2619 -7.925500e+02 7.389900e+02 +1 2620 -1.462630e+03 9.058199e+02 +2 2620 -5.436800e+02 4.675900e+02 +9 2620 -5.246300e+02 4.878700e+02 +11 2620 1.371100e+02 4.134000e+02 +1 2621 1.373600e+02 -7.566899e+02 +3 2621 6.167900e+02 -6.836400e+02 +6 2621 -6.734003e+01 -5.623300e+02 +1 2622 1.562000e+02 -6.748700e+02 +3 2622 6.369500e+02 -5.928500e+02 +1 2623 9.208201e+02 -6.143500e+02 +6 2623 7.872700e+02 -4.968300e+02 +1 2624 9.208201e+02 -6.143500e+02 +6 2624 7.872700e+02 -4.968300e+02 +1 2625 -1.183700e+03 -6.068400e+02 +6 2625 -7.427300e+02 -4.160400e+02 +1 2626 -1.225520e+03 -5.978900e+02 +6 2626 -7.718900e+02 -4.087000e+02 +1 2627 -1.067570e+03 -5.711200e+02 +3 2627 -1.026500e+03 -4.966100e+02 +1 2628 1.069700e+02 -5.699900e+02 +3 2628 5.735000e+02 -4.774301e+02 +1 2629 -9.831700e+02 -5.674000e+02 +3 2629 -9.445200e+02 -4.918800e+02 +6 2629 -5.886400e+02 -3.962600e+02 +1 2630 -9.498100e+02 -5.656500e+02 +3 2630 -9.123800e+02 -4.895000e+02 +1 2631 -9.498100e+02 -5.656500e+02 +3 2631 -9.123800e+02 -4.895000e+02 +1 2632 1.127900e+02 -5.649200e+02 +3 2632 5.801300e+02 -4.730601e+02 +1 2633 -9.454600e+02 -5.637700e+02 +3 2633 -9.081200e+02 -4.875300e+02 +1 2634 1.196899e+02 -5.608900e+02 +6 2634 -6.842999e+01 -4.145300e+02 +1 2635 1.196899e+02 -5.608900e+02 +6 2635 -6.842999e+01 -4.145300e+02 +1 2636 -8.885800e+02 -5.594301e+02 +3 2636 -8.541700e+02 -4.819301e+02 +1 2637 1.250699e+02 -5.527200e+02 +3 2637 5.944100e+02 -4.590100e+02 +6 2637 -6.402002e+01 -4.083600e+02 +1 2638 1.150100e+02 -5.493800e+02 +6 2638 -7.171002e+01 -4.053700e+02 +1 2639 1.150100e+02 -5.493800e+02 +6 2639 -7.171002e+01 -4.053700e+02 +1 2640 1.555601e+02 -5.489000e+02 +3 2640 6.265500e+02 -4.539100e+02 +1 2641 1.370800e+02 -5.490500e+02 +3 2641 6.082500e+02 -4.537800e+02 +6 2641 -5.413000e+01 -4.058800e+02 +1 2642 1.444900e+02 -5.465000e+02 +6 2642 -4.933002e+01 -4.039301e+02 +1 2643 1.124600e+02 -5.300800e+02 +3 2643 5.828600e+02 -4.331801e+02 +6 2643 -7.297998e+01 -3.909000e+02 +1 2644 1.303199e+02 -5.184700e+02 +6 2644 -5.921002e+01 -3.822400e+02 +1 2645 -1.073080e+03 -5.111600e+02 +3 2645 -1.024990e+03 -4.331300e+02 +1 2646 1.289200e+02 -5.104700e+02 +3 2646 5.977500e+02 -4.114000e+02 +1 2647 -3.004500e+02 -4.959200e+02 +3 2647 -3.913400e+02 -4.114399e+02 +1 2648 -1.066230e+03 -4.958700e+02 +6 2648 -6.503700e+02 -3.439500e+02 +1 2649 -1.004290e+03 -4.955000e+02 +6 2649 -6.034600e+02 -3.460601e+02 +1 2650 8.465002e+01 -4.746600e+02 +6 2650 -8.603998e+01 -3.483300e+02 +1 2651 8.101001e+01 -4.707300e+02 +3 2651 5.383900e+02 -3.681200e+02 +1 2652 8.448401e+02 -4.684100e+02 +2 2652 6.710800e+02 -2.545100e+02 +1 2653 -8.229900e+02 -4.573199e+02 +6 2653 -4.609200e+02 -3.263700e+02 +1 2654 -5.842400e+02 -4.545500e+02 +6 2654 -2.602000e+02 -3.347000e+02 +1 2655 -7.450600e+02 -4.537600e+02 +6 2655 -3.962200e+02 -3.274900e+02 +1 2656 -8.800600e+02 -4.425300e+02 +3 2656 -8.518500e+02 -3.579200e+02 +1 2657 -5.230100e+02 -4.413500e+02 +6 2657 -2.048100e+02 -3.281700e+02 +1 2658 -6.024500e+02 -4.390200e+02 +6 2658 -3.134100e+02 -3.208300e+02 +1 2659 -1.053250e+03 -4.357600e+02 +3 2659 -1.016700e+03 -3.525699e+02 +1 2660 -8.303800e+02 -4.326600e+02 +6 2660 -4.659400e+02 -3.094700e+02 +1 2661 -8.667300e+02 -4.316000e+02 +3 2661 -8.400900e+02 -3.475601e+02 +1 2662 -1.002070e+03 -4.307300e+02 +6 2662 -6.031300e+02 -3.011900e+02 +1 2663 -1.012890e+03 -4.303300e+02 +6 2663 -6.117900e+02 -3.003800e+02 +1 2664 -8.449300e+02 -4.261700e+02 +6 2664 -4.779500e+02 -3.041300e+02 +1 2665 -8.449300e+02 -4.261700e+02 +6 2665 -4.779500e+02 -3.041300e+02 +1 2666 -8.299000e+02 -4.255900e+02 +3 2666 -8.093600e+02 -3.405900e+02 +1 2667 -1.011290e+03 -4.235400e+02 +6 2667 -6.104100e+02 -2.964700e+02 +1 2668 -7.884700e+02 -4.232500e+02 +6 2668 -4.324900e+02 -3.042500e+02 +1 2669 -4.871500e+02 -4.220300e+02 +6 2669 -1.694900e+02 -3.169700e+02 +1 2670 -9.749200e+02 -4.199900e+02 +6 2670 -5.826800e+02 -2.949800e+02 +1 2671 -7.722100e+02 -4.189500e+02 +3 2671 -7.582200e+02 -3.331200e+02 +1 2672 1.326400e+02 -4.184301e+02 +6 2672 -5.351001e+01 -3.071500e+02 +1 2673 1.326400e+02 -4.184301e+02 +3 2673 6.020300e+02 -3.091801e+02 +1 2674 -8.572600e+02 -4.185000e+02 +6 2674 -4.884900e+02 -2.984500e+02 +1 2675 -9.980600e+02 -4.164100e+02 +6 2675 -6.001300e+02 -2.917800e+02 +1 2676 -4.382400e+02 -4.114399e+02 +6 2676 -1.309900e+02 -3.109700e+02 +1 2677 -7.879600e+02 -4.091200e+02 +3 2677 -7.702100e+02 -3.228400e+02 +1 2678 1.367100e+02 -4.086200e+02 +6 2678 -4.998999e+01 -2.995100e+02 +1 2679 -8.858400e+02 -4.068900e+02 +3 2679 -8.544300e+02 -3.205601e+02 +1 2680 -8.536200e+02 -3.976400e+02 +3 2680 -8.242800e+02 -3.109301e+02 +1 2681 -9.763800e+02 -3.939800e+02 +6 2681 -5.861800e+02 -2.769000e+02 +1 2682 -1.240560e+03 -3.924800e+02 +6 2682 -8.218300e+02 -2.648200e+02 +1 2683 7.882100e+02 -3.890800e+02 +3 2683 7.939100e+02 -2.918700e+02 +1 2684 7.939900e+02 -3.882600e+02 +3 2684 8.002800e+02 -2.909100e+02 +1 2685 -4.609301e+02 -3.809600e+02 +6 2685 -1.462500e+02 -2.901700e+02 +1 2686 -1.966100e+02 -3.761300e+02 +3 2686 -3.296200e+02 -2.911200e+02 +1 2687 -4.742700e+02 -3.732400e+02 +6 2687 -1.575200e+02 -2.835300e+02 +1 2688 -4.797400e+02 -3.696600e+02 +6 2688 -1.616600e+02 -2.808400e+02 +1 2689 -7.547100e+02 -3.676899e+02 +3 2689 -7.408200e+02 -2.791000e+02 +6 2689 -4.054600e+02 -2.671900e+02 +13 2689 -1.602290e+03 -2.499900e+02 +1 2690 6.897998e+01 -3.643600e+02 +6 2690 -9.452002e+01 -2.650000e+02 +1 2691 1.363900e+02 -3.630601e+02 +3 2691 6.078600e+02 -2.475900e+02 +1 2692 -5.503700e+02 -3.631700e+02 +6 2692 -2.289000e+02 -2.728600e+02 +1 2693 5.049500e+02 -3.626600e+02 +3 2693 3.711000e+02 -2.717400e+02 +1 2694 7.730100e+02 -3.618101e+02 +3 2694 7.778101e+02 -2.642900e+02 +1 2695 4.897400e+02 -3.585900e+02 +3 2695 3.581500e+02 -2.687200e+02 +17 2695 -1.576060e+03 8.673999e+01 +1 2696 -7.630005e+00 -3.520400e+02 +8 2696 6.407800e+02 -1.487600e+02 +1 2697 -6.170700e+02 -3.519900e+02 +6 2697 -3.369200e+02 -2.577400e+02 +1 2698 -5.110400e+02 -3.505000e+02 +6 2698 -1.925800e+02 -2.658900e+02 +1 2699 -1.367900e+03 -3.367200e+02 +6 2699 -8.651400e+02 -2.254300e+02 +1 2700 -1.093000e+02 -3.189301e+02 +2 2700 -5.753003e+01 -1.250900e+02 +3 2700 -2.688800e+02 -2.346400e+02 +1 2701 -5.762200e+02 -3.142800e+02 +6 2701 -2.500900e+02 -2.380600e+02 +1 2702 -1.141500e+02 -3.067500e+02 +3 2702 -2.746700e+02 -2.230900e+02 +1 2703 -5.544700e+02 -3.064600e+02 +6 2703 -2.304500e+02 -2.328500e+02 +1 2704 -1.128530e+03 -2.874600e+02 +3 2704 -1.092930e+03 -1.929301e+02 +1 2705 -9.196600e+02 -2.807300e+02 +3 2705 -8.888300e+02 -1.864200e+02 +1 2706 -9.196600e+02 -2.807300e+02 +3 2706 -8.888300e+02 -1.864200e+02 +1 2707 -1.095670e+03 -2.745900e+02 +2 2707 -3.441600e+02 -1.688300e+02 +6 2707 -6.713900e+02 -1.908700e+02 +1 2708 8.641101e+02 -2.734000e+02 +3 2708 9.103101e+02 -1.730900e+02 +1 2709 8.439500e+02 -2.727900e+02 +2 2709 6.726500e+02 -1.438500e+02 +1 2710 -1.211710e+03 -2.718900e+02 +6 2710 -7.537000e+02 -1.854100e+02 +1 2711 9.022000e+02 -2.675601e+02 +3 2711 9.514199e+02 -1.663700e+02 +8 2711 7.727100e+02 -1.014100e+02 +1 2712 9.070701e+02 -2.671801e+02 +3 2712 9.564299e+02 -1.660900e+02 +1 2713 1.104600e+03 -2.640200e+02 +6 2713 9.282800e+02 -2.417100e+02 +8 2713 9.114301e+02 -1.005500e+02 +1 2714 1.218910e+03 -2.612800e+02 +8 2714 9.999700e+02 -9.798999e+01 +1 2715 9.702500e+02 -2.593700e+02 +3 2715 1.027880e+03 -1.573900e+02 +8 2715 8.150300e+02 -9.528003e+01 +17 2715 -9.732600e+02 1.146801e+02 +1 2716 8.252300e+02 -2.562400e+02 +3 2716 8.534399e+02 -1.566600e+02 +1 2717 3.545400e+02 -2.504600e+02 +2 2717 7.453998e+01 4.291998e+01 +3 2717 -7.449951e+00 -1.775800e+02 +13 2717 -1.418000e+02 2.999099e+02 +1 2718 -1.336500e+02 -2.495699e+02 +6 2718 1.629200e+02 -2.150100e+02 +1 2719 9.939900e+02 -2.392700e+02 +3 2719 1.054790e+03 -1.370800e+02 +17 2719 -9.520600e+02 1.304100e+02 +1 2720 -1.447900e+02 -2.375601e+02 +3 2720 -2.980400e+02 -1.535700e+02 +6 2720 1.537000e+02 -2.060000e+02 +8 2720 2.281400e+02 -5.795001e+01 +13 2720 -9.963100e+02 6.775000e+01 +1 2721 3.357100e+02 -2.079301e+02 +2 2721 5.523999e+01 8.704999e+01 +3 2721 -2.538000e+01 -1.376700e+02 +11 2721 6.964100e+02 2.665300e+02 +13 2721 -1.915200e+02 4.124500e+02 +1 2722 5.356100e+02 -1.991700e+02 +3 2722 3.855400e+02 -1.135400e+02 +1 2723 -1.612600e+02 -1.986100e+02 +6 2723 1.375601e+02 -1.788700e+02 +1 2724 -1.925300e+02 -1.977200e+02 +3 2724 -3.284300e+02 -1.120200e+02 +1 2725 7.692500e+02 -1.967600e+02 +2 2725 6.250200e+02 -9.307001e+01 +3 2725 7.736500e+02 -9.778998e+01 +6 2725 7.076600e+02 -1.874000e+02 +17 2725 -1.169710e+03 1.892600e+02 +1 2726 8.455500e+02 -1.950000e+02 +2 2726 6.737100e+02 -9.907001e+01 +1 2727 7.653401e+02 -1.941500e+02 +3 2727 7.702800e+02 -9.537000e+01 +17 2727 -1.173240e+03 1.922300e+02 +1 2728 -5.271600e+02 -1.935300e+02 +6 2728 -2.038100e+02 -1.569000e+02 +1 2729 2.701801e+02 -1.904600e+02 +2 2729 -1.396997e+01 1.053400e+02 +9 2729 6.506995e+01 3.544299e+02 +10 2729 7.865002e+01 -3.698199e+02 +13 2729 -3.702500e+02 4.645100e+02 +1 2730 -5.025700e+02 -1.902900e+02 +3 2730 -5.407900e+02 -9.650000e+01 +1 2731 -1.405770e+03 -1.897600e+02 +6 2731 -9.108300e+02 -1.221000e+02 +1 2732 5.975400e+02 -1.699600e+02 +2 2732 4.831200e+02 -3.414001e+01 +3 2732 4.762000e+02 -8.064001e+01 +1 2733 -2.165002e+01 -1.587800e+02 +6 2733 3.346100e+02 -1.655200e+02 +1 2734 -2.165002e+01 -1.587800e+02 +6 2734 3.346100e+02 -1.655200e+02 +8 2734 6.323000e+02 4.178003e+01 +1 2735 -1.148500e+02 -1.442100e+02 +2 2735 -6.316998e+01 4.679993e+00 +3 2735 -2.771400e+02 -5.937000e+01 +13 2735 -9.532600e+02 2.495601e+02 +1 2736 8.079700e+02 -1.359200e+02 +2 2736 6.498600e+02 -5.917999e+01 +1 2737 -3.896997e+01 -1.332700e+02 +6 2737 3.236899e+02 -1.479300e+02 +1 2738 3.305500e+02 -1.284600e+02 +2 2738 4.872998e+01 1.709400e+02 +3 2738 -3.040002e+01 -6.233002e+01 +11 2738 6.918000e+02 3.430500e+02 +13 2738 -2.033300e+02 6.318201e+02 +18 2738 -1.672000e+02 1.335100e+02 +1 2739 -2.235999e+01 -1.173600e+02 +6 2739 3.353199e+02 -1.374600e+02 +8 2739 6.318600e+02 8.296997e+01 +1 2740 -2.235999e+01 -1.173600e+02 +6 2740 3.353199e+02 -1.374600e+02 +8 2740 6.318600e+02 8.296997e+01 +1 2741 -3.629100e+02 -1.024600e+02 +3 2741 -4.373700e+02 -9.380005e+00 +13 2741 -1.218680e+03 2.205300e+02 +1 2742 8.487200e+02 -8.545996e+01 +3 2742 8.904800e+02 1.790997e+01 +1 2743 1.182960e+03 -7.716003e+01 +6 2743 8.467800e+02 -8.214001e+01 +1 2744 1.197260e+03 -7.666003e+01 +6 2744 8.585900e+02 -8.215002e+01 +1 2745 8.518501e+02 -7.479004e+01 +2 2745 6.781600e+02 -3.141998e+01 +3 2745 8.942000e+02 2.831000e+01 +1 2746 9.398101e+02 -7.368994e+01 +2 2746 7.283800e+02 -3.529999e+01 +3 2746 9.952500e+02 3.056000e+01 +1 2747 9.713101e+02 -7.067004e+01 +3 2747 1.030240e+03 3.394000e+01 +8 2747 8.162400e+02 6.252002e+01 +17 2747 -9.694800e+02 2.740500e+02 +1 2748 1.047610e+03 -7.001001e+01 +6 2748 8.893300e+02 -9.606000e+01 +17 2748 -9.046300e+02 2.711400e+02 +1 2749 -8.336000e+02 -6.971997e+01 +3 2749 -8.152200e+02 3.735999e+01 +1 2750 1.047350e+03 -6.566003e+01 +2 2750 7.886700e+02 -3.363000e+01 +8 2750 8.701899e+02 6.653003e+01 +17 2750 -9.043400e+02 2.745400e+02 +1 2751 9.840300e+02 -6.559998e+01 +3 2751 1.043640e+03 3.942999e+01 +1 2752 1.097570e+03 -6.283997e+01 +6 2752 9.269500e+02 -9.153998e+01 +17 2752 -8.625600e+02 2.752100e+02 +1 2753 -1.075300e+02 -6.222998e+01 +8 2753 3.282900e+02 1.092700e+02 +13 2753 -9.887200e+02 4.511200e+02 +1 2754 7.796699e+02 -6.073999e+01 +2 2754 6.321200e+02 -1.103003e+01 +3 2754 7.854500e+02 4.023999e+01 +1 2755 1.141340e+03 -5.777002e+01 +8 2755 9.412800e+02 7.265002e+01 +1 2756 -5.279004e+01 -5.581995e+01 +8 2756 6.022700e+02 1.434500e+02 +1 2757 -4.315500e+02 -5.396997e+01 +2 2757 -1.391500e+02 9.440002e+00 +13 2757 -1.296150e+03 2.801200e+02 +1 2758 -5.198800e+02 -5.100000e+01 +6 2758 -1.937900e+02 -5.960999e+01 +1 2759 -5.198800e+02 -5.100000e+01 +6 2759 -1.937900e+02 -5.960999e+01 +1 2760 -1.020530e+03 -4.256006e+01 +6 2760 -6.104700e+02 -3.381000e+01 +1 2761 -1.113490e+03 -4.121997e+01 +6 2761 -6.785000e+02 -3.056000e+01 +1 2762 1.078090e+03 -3.737000e+01 +6 2762 9.123400e+02 -7.235999e+01 +1 2763 1.206200e+03 -3.492004e+01 +6 2763 8.666300e+02 -5.069000e+01 +1 2764 -1.115780e+03 -3.437000e+01 +3 2764 -1.084590e+03 7.939001e+01 +6 2764 -6.798000e+02 -2.565997e+01 +1 2765 -1.115780e+03 -3.437000e+01 +3 2765 -1.084590e+03 7.939001e+01 +1 2766 1.120040e+03 -3.414001e+01 +6 2766 9.445100e+02 -7.048999e+01 +1 2767 1.107470e+03 -3.279004e+01 +6 2767 9.347700e+02 -6.933002e+01 +1 2768 8.849099e+02 -3.244995e+01 +3 2768 9.325100e+02 7.275000e+01 +6 2768 7.753300e+02 -6.600000e+01 +1 2769 1.098130e+03 -3.021997e+01 +8 2769 9.077900e+02 9.581000e+01 +1 2770 1.086930e+03 -2.937000e+01 +8 2770 8.994000e+02 9.626001e+01 +1 2771 7.648999e+02 -2.781006e+01 +6 2771 7.084800e+02 -6.491998e+01 +1 2772 -5.731900e+02 -1.348999e+01 +3 2772 -5.979600e+02 9.007001e+01 +1 2773 9.262700e+02 -4.820007e+00 +6 2773 8.061300e+02 -4.690002e+01 +1 2774 -4.534900e+02 1.059003e+01 +6 2774 -1.294700e+02 -2.070001e+01 +1 2775 -1.559301e+02 1.459998e+01 +6 2775 1.769600e+02 -3.690002e+01 +1 2776 -5.062700e+02 2.170001e+01 +3 2776 -5.415400e+02 1.245600e+02 +1 2777 -3.450500e+02 3.584998e+01 +6 2777 -3.354999e+01 -7.880005e+00 +1 2778 -2.890900e+02 3.629004e+01 +6 2778 2.118005e+01 -1.038000e+01 +1 2779 -9.240400e+02 3.934009e+01 +2 2779 -2.835600e+02 1.033002e+01 +1 2780 -1.109630e+03 4.357007e+01 +6 2780 -6.729900e+02 2.720001e+01 +1 2781 -1.114380e+03 5.468994e+01 +3 2781 -1.087650e+03 1.757200e+02 +1 2782 -3.971300e+02 5.558008e+01 +6 2782 -7.722998e+01 8.179993e+00 +1 2783 7.630701e+02 5.975000e+01 +3 2783 7.671200e+02 1.610000e+02 +17 2783 -1.173800e+03 4.229199e+02 +1 2784 -1.116790e+03 6.465991e+01 +3 2784 -1.091370e+03 1.863000e+02 +1 2785 -1.081800e+03 6.577002e+01 +3 2785 -1.055990e+03 1.871400e+02 +1 2786 -1.081800e+03 6.577002e+01 +2 2786 -3.452300e+02 1.607001e+01 +3 2786 -1.055990e+03 1.871400e+02 +1 2787 -4.670000e+02 8.335999e+01 +3 2787 -5.205900e+02 1.860000e+02 +13 2787 -1.331810e+03 4.869700e+02 +1 2788 -4.781700e+02 8.748999e+01 +6 2788 -1.495700e+02 3.303998e+01 +1 2789 9.128501e+02 9.859009e+01 +2 2789 7.142600e+02 6.473999e+01 +1 2790 -3.892500e+02 1.046100e+02 +6 2790 -6.951001e+01 4.003003e+01 +1 2791 -5.167400e+02 1.063700e+02 +6 2791 -1.868700e+02 4.773999e+01 +1 2792 -5.175100e+02 1.161300e+02 +3 2792 -5.554100e+02 2.225901e+02 +6 2792 -1.869200e+02 5.594000e+01 +1 2793 7.586101e+02 1.182000e+02 +3 2793 7.653300e+02 2.218000e+02 +1 2794 1.062130e+03 1.298900e+02 +6 2794 9.056000e+02 5.108002e+01 +1 2795 9.533899e+02 1.309800e+02 +3 2795 1.009870e+03 2.388800e+02 +1 2796 9.861499e+02 1.352200e+02 +6 2796 8.503500e+02 5.609003e+01 +1 2797 -8.858700e+02 1.386300e+02 +3 2797 -8.680700e+02 2.613201e+02 +1 2798 -3.665300e+02 1.413600e+02 +2 2798 -1.185700e+02 1.452700e+02 +3 2798 -4.428700e+02 2.409800e+02 +6 2798 -5.108002e+01 6.623999e+01 +8 2798 -1.113000e+02 2.519700e+02 +13 2798 -1.220320e+03 6.193000e+02 +1 2799 1.020470e+03 1.441500e+02 +6 2799 8.740601e+02 6.269000e+01 +1 2800 1.137080e+03 1.463401e+02 +6 2800 9.620000e+02 6.327002e+01 +1 2801 -1.971400e+02 1.467000e+02 +6 2801 1.549399e+02 5.347998e+01 +8 2801 2.558199e+02 3.020900e+02 +13 2801 -1.174890e+03 8.847900e+02 +1 2802 1.163790e+03 1.472900e+02 +6 2802 9.825900e+02 6.376001e+01 +8 2802 9.631899e+02 2.459300e+02 +1 2803 -5.149200e+02 1.496300e+02 +3 2803 -5.533300e+02 2.575901e+02 +6 2803 -1.843500e+02 7.914001e+01 +1 2804 -2.078101e+02 1.529000e+02 +6 2804 1.475100e+02 5.771002e+01 +8 2804 2.454900e+02 3.079100e+02 +1 2805 8.032800e+02 1.564500e+02 +3 2805 8.375300e+02 2.639299e+02 +1 2806 -2.106899e+02 1.614600e+02 +6 2806 1.464500e+02 6.326001e+01 +1 2807 -5.102200e+02 1.658900e+02 +3 2807 -5.490500e+02 2.748800e+02 +13 2807 -1.364210e+03 5.902700e+02 +1 2808 -7.183700e+02 1.719700e+02 +6 2808 -3.530100e+02 1.016600e+02 +1 2809 -8.213300e+02 1.736200e+02 +3 2809 -8.131800e+02 2.966100e+02 +1 2810 -3.584700e+02 1.795200e+02 +3 2810 -4.335900e+02 2.807100e+02 +6 2810 -4.544000e+01 9.200000e+01 +1 2811 7.819800e+02 1.804900e+02 +2 2811 6.343700e+02 1.339400e+02 +17 2811 -1.155500e+03 5.350200e+02 +1 2812 1.130260e+03 1.857700e+02 +6 2812 9.574301e+02 9.300000e+01 +1 2813 1.138280e+03 1.860100e+02 +8 2813 9.486801e+02 2.786799e+02 +1 2814 6.893000e+02 1.865701e+02 +3 2814 6.601100e+02 2.843900e+02 +17 2814 -1.263010e+03 5.686699e+02 +1 2815 -4.290601e+02 2.003700e+02 +3 2815 -4.919800e+02 3.055500e+02 +1 2816 -5.818500e+02 2.007300e+02 +3 2816 -6.081500e+02 3.150000e+02 +6 2816 -2.407600e+02 1.163200e+02 +13 2816 -1.439950e+03 6.198301e+02 +1 2817 -5.775500e+02 2.024500e+02 +6 2817 -2.372100e+02 1.177900e+02 +1 2818 -3.868700e+02 2.028600e+02 +3 2818 -4.599900e+02 3.045701e+02 +1 2819 7.501399e+02 2.079500e+02 +3 2819 7.534000e+02 3.126100e+02 +17 2819 -1.185070e+03 5.631000e+02 +1 2820 -5.805200e+02 2.123401e+02 +3 2820 -6.090400e+02 3.271799e+02 +1 2821 6.646799e+02 2.203700e+02 +3 2821 6.326400e+02 3.205400e+02 +1 2822 -6.063400e+02 2.226200e+02 +3 2822 -6.302300e+02 3.387000e+02 +13 2822 -1.466430e+03 6.456100e+02 +1 2823 1.185200e+03 2.253401e+02 +6 2823 1.000110e+03 1.221800e+02 +1 2824 -3.062800e+02 2.350901e+02 +8 2824 3.489001e+01 3.546200e+02 +1 2825 -5.710100e+02 2.348500e+02 +3 2825 -5.994600e+02 3.501400e+02 +6 2825 -2.316700e+02 1.398200e+02 +13 2825 -1.426600e+03 6.742100e+02 +1 2826 7.551299e+02 2.381699e+02 +3 2826 7.585000e+02 3.423300e+02 +1 2827 -2.076801e+02 2.384299e+02 +2 2827 -1.881700e+02 3.297500e+02 +8 2827 2.477800e+02 3.874299e+02 +13 2827 -1.197630e+03 1.074730e+03 +1 2828 7.761899e+02 2.393401e+02 +6 2828 7.232700e+02 1.287100e+02 +1 2829 -1.302080e+03 2.388301e+02 +6 2829 -8.004400e+02 1.640500e+02 +1 2830 -5.391100e+02 2.414700e+02 +6 2830 -2.053800e+02 1.433800e+02 +1 2831 -3.139301e+02 2.419800e+02 +8 2831 2.831995e+01 3.600800e+02 +1 2832 -5.161800e+02 2.426200e+02 +6 2832 -1.840500e+02 1.427400e+02 +1 2833 -3.115300e+02 2.469700e+02 +6 2833 3.147998e+01 1.307300e+02 +1 2834 -3.115300e+02 2.469700e+02 +6 2834 3.147998e+01 1.307300e+02 +1 2835 9.636799e+02 2.560100e+02 +6 2835 8.367700e+02 1.447700e+02 +17 2835 -9.720900e+02 5.566400e+02 +1 2836 9.636799e+02 2.560100e+02 +3 2836 1.021150e+03 3.666000e+02 +17 2836 -9.720900e+02 5.566400e+02 +1 2837 9.177400e+02 2.660400e+02 +6 2837 8.056600e+02 1.516800e+02 +1 2838 -7.258200e+02 2.683201e+02 +3 2838 -7.324500e+02 3.926799e+02 +1 2839 -7.412500e+02 2.788900e+02 +3 2839 -7.434000e+02 4.034900e+02 +1 2840 -5.342400e+02 2.833700e+02 +6 2840 -2.026100e+02 1.720800e+02 +13 2840 -1.378630e+03 7.547000e+02 +1 2841 -5.271300e+02 2.863700e+02 +6 2841 -1.977600e+02 1.743200e+02 +1 2842 -5.398000e+02 2.870300e+02 +6 2842 -2.065700e+02 1.749600e+02 +13 2842 -1.385100e+03 7.595500e+02 +1 2843 -5.566500e+02 2.874199e+02 +3 2843 -5.873200e+02 4.043500e+02 +6 2843 -2.180300e+02 1.751800e+02 +1 2844 -6.166700e+02 2.935901e+02 +6 2844 -2.674800e+02 1.812900e+02 +1 2845 8.104800e+02 3.201400e+02 +3 2845 8.446300e+02 4.311000e+02 +1 2846 -7.438700e+02 3.211400e+02 +6 2846 -3.760500e+02 2.056800e+02 +1 2847 8.178999e+02 3.241699e+02 +3 2847 8.549000e+02 4.354200e+02 +1 2848 9.622900e+02 3.323800e+02 +3 2848 1.020820e+03 4.453101e+02 +1 2849 1.112970e+03 3.331200e+02 +8 2849 9.259800e+02 4.032500e+02 +1 2850 9.412700e+02 3.818900e+02 +3 2850 9.971299e+02 4.954100e+02 +1 2851 -7.761600e+02 3.878500e+02 +3 2851 -7.706100e+02 5.242000e+02 +1 2852 -5.904400e+02 4.181100e+02 +8 2852 -3.247100e+02 4.718700e+02 +1 2853 -1.343460e+03 4.229500e+02 +6 2853 -8.225400e+02 2.894200e+02 +1 2854 -5.957200e+02 4.431100e+02 +3 2854 -6.655900e+02 5.606400e+02 +1 2855 -9.312800e+02 4.470701e+02 +3 2855 -9.112500e+02 5.964399e+02 +1 2856 -5.979700e+02 4.496699e+02 +6 2856 -2.142700e+02 2.814700e+02 +1 2857 -9.678100e+02 4.564000e+02 +3 2857 -9.474200e+02 6.081000e+02 +1 2858 9.880100e+02 4.591300e+02 +3 2858 9.903799e+02 5.647300e+02 +1 2859 9.880100e+02 4.591300e+02 +3 2859 9.903799e+02 5.647300e+02 +1 2860 1.006670e+03 4.593201e+02 +3 2860 1.008800e+03 5.644399e+02 +1 2861 1.006670e+03 4.593201e+02 +3 2861 1.008800e+03 5.644399e+02 +1 2862 -9.837500e+02 4.597600e+02 +3 2862 -9.632000e+02 6.122600e+02 +1 2863 9.928201e+02 4.602800e+02 +3 2863 9.950200e+02 5.658000e+02 +17 2863 -9.604600e+02 7.878600e+02 +1 2864 1.002280e+03 4.606599e+02 +3 2864 1.004330e+03 5.656600e+02 +1 2865 -9.974800e+02 4.628500e+02 +3 2865 -9.768400e+02 6.163900e+02 +8 2865 -7.866400e+02 4.453300e+02 +1 2866 -6.688000e+02 4.735000e+02 +6 2866 -2.602700e+02 2.979400e+02 +1 2867 -1.260240e+03 4.941000e+02 +2 2867 -4.331400e+02 2.440800e+02 +1 2868 7.045801e+02 4.987200e+02 +3 2868 5.994700e+02 5.892600e+02 +1 2869 8.401499e+02 5.059700e+02 +6 2869 8.345601e+02 3.077400e+02 +1 2870 -7.752300e+02 5.211100e+02 +3 2870 -7.790900e+02 6.649700e+02 +1 2871 9.039099e+02 5.290000e+02 +3 2871 7.969301e+02 6.163300e+02 +1 2872 7.253000e+02 5.334000e+02 +3 2872 6.213800e+02 6.238600e+02 +6 2872 7.508300e+02 3.269900e+02 +1 2873 -9.053700e+02 5.466000e+02 +3 2873 -8.936400e+02 7.016799e+02 +1 2874 -9.053700e+02 5.466000e+02 +3 2874 -8.936400e+02 7.016799e+02 +1 2875 -8.440100e+02 5.584000e+02 +3 2875 -8.369100e+02 7.103101e+02 +1 2876 -1.341480e+03 5.587000e+02 +6 2876 -8.179300e+02 3.813900e+02 +1 2877 -9.045900e+02 5.725200e+02 +3 2877 -8.932100e+02 7.284800e+02 +1 2878 -8.330100e+02 6.102700e+02 +6 2878 -4.440900e+02 4.069200e+02 +1 2879 -8.589600e+02 6.105601e+02 +3 2879 -8.508200e+02 7.677200e+02 +1 2880 -8.813000e+02 6.364600e+02 +3 2880 -8.697200e+02 7.980300e+02 +1 2881 -1.077600e+03 6.419000e+02 +6 2881 -6.303900e+02 4.345601e+02 +1 2882 8.468000e+02 6.457000e+02 +2 2882 6.629100e+02 5.218600e+02 +3 2882 7.368600e+02 7.344399e+02 +1 2883 -1.366460e+03 6.574100e+02 +2 2883 -4.884800e+02 3.305900e+02 +1 2884 -1.245800e+03 6.790500e+02 +6 2884 -7.477900e+02 4.620100e+02 +1 2885 -1.042290e+03 7.138101e+02 +8 2885 -8.186000e+02 6.358400e+02 +1 2886 -8.686000e+02 7.390100e+02 +6 2886 -4.637800e+02 4.948700e+02 +1 2887 -8.740100e+02 7.411899e+02 +6 2887 -4.682600e+02 4.963201e+02 +1 2888 -1.405670e+03 7.648500e+02 +2 2888 -5.132100e+02 3.913400e+02 +1 2889 -1.120830e+03 7.750500e+02 +8 2889 -8.839200e+02 6.759100e+02 +1 2890 -8.841500e+02 8.320400e+02 +6 2890 -4.718000e+02 5.584800e+02 +1 2891 -1.178450e+03 8.798700e+02 +6 2891 -6.965200e+02 5.981000e+02 +1 2892 1.393300e+02 -7.636300e+02 +3 2892 6.206300e+02 -6.903500e+02 +1 2893 1.736300e+02 -7.277500e+02 +3 2893 6.563800e+02 -6.506100e+02 +1 2894 1.576300e+02 -6.903300e+02 +3 2894 6.392300e+02 -6.096300e+02 +1 2895 1.995699e+02 -6.881100e+02 +6 2895 -1.892999e+01 -5.130300e+02 +1 2896 9.137100e+02 -6.205100e+02 +6 2896 7.819000e+02 -5.009399e+02 +1 2897 9.072300e+02 -6.138700e+02 +6 2897 7.770500e+02 -4.959200e+02 +1 2898 -1.075520e+03 -5.722900e+02 +3 2898 -1.034160e+03 -4.980800e+02 +6 2898 -6.641500e+02 -3.959100e+02 +1 2899 -1.075520e+03 -5.722900e+02 +6 2899 -6.641500e+02 -3.959100e+02 +1 2900 -9.955700e+02 -5.696500e+02 +6 2900 -6.037800e+02 -3.980200e+02 +1 2901 -9.830700e+02 -5.637100e+02 +3 2901 -9.445300e+02 -4.880400e+02 +1 2902 -9.830700e+02 -5.637100e+02 +3 2902 -9.445300e+02 -4.880400e+02 +1 2903 1.142060e+03 -5.614301e+02 +6 2903 9.505699e+02 -4.655100e+02 +1 2904 1.173900e+02 -5.575800e+02 +6 2904 -6.959998e+01 -4.114700e+02 +1 2905 1.523400e+02 -5.541700e+02 +6 2905 -4.276001e+01 -4.103400e+02 +1 2906 1.717400e+02 -5.530601e+02 +6 2906 -2.370001e+01 -4.104000e+02 +1 2907 1.110800e+02 -5.478400e+02 +3 2907 5.804200e+02 -4.538900e+02 +6 2907 -7.471002e+01 -4.041000e+02 +1 2908 7.679900e+02 -5.460800e+02 +3 2908 7.729100e+02 -4.490300e+02 +1 2909 1.290699e+02 -5.455300e+02 +6 2909 -6.104999e+01 -4.030200e+02 +1 2910 -1.073810e+03 -5.453800e+02 +3 2910 -1.025390e+03 -4.689301e+02 +1 2911 1.455300e+02 -5.423700e+02 +3 2911 6.158199e+02 -4.463000e+02 +1 2912 1.065900e+02 -5.404000e+02 +3 2912 5.742700e+02 -4.448000e+02 +1 2913 1.585200e+02 -5.374600e+02 +6 2913 -3.750000e+01 -3.977800e+02 +1 2914 1.111100e+02 -5.244200e+02 +3 2914 5.809200e+02 -4.267600e+02 +1 2915 1.367200e+02 -5.155900e+02 +3 2915 6.069800e+02 -4.171100e+02 +1 2916 1.513101e+02 -5.107200e+02 +6 2916 -4.129999e+01 -3.776000e+02 +1 2917 1.434399e+02 -5.109700e+02 +3 2917 6.139500e+02 -4.114800e+02 +1 2918 7.417004e+01 -5.094700e+02 +3 2918 5.324900e+02 -4.109100e+02 +1 2919 7.417004e+01 -5.094700e+02 +3 2919 5.324900e+02 -4.109100e+02 +1 2920 1.525000e+02 -5.076500e+02 +3 2920 6.231200e+02 -4.080800e+02 +1 2921 7.450000e+01 -5.058300e+02 +3 2921 5.325100e+02 -4.070000e+02 +1 2922 7.911499e+02 -4.970699e+02 +3 2922 7.975400e+02 -3.997200e+02 +1 2923 -9.828500e+02 -4.901400e+02 +3 2923 -1.031380e+03 -4.108500e+02 +1 2924 -5.192000e+02 -4.809600e+02 +6 2924 -2.026100e+02 -3.559399e+02 +1 2925 1.077500e+02 -4.780400e+02 +3 2925 5.737400e+02 -3.755400e+02 +1 2926 1.379200e+02 -4.743400e+02 +6 2926 -5.094000e+01 -3.499100e+02 +1 2927 7.976001e+01 -4.744100e+02 +6 2927 -8.957001e+01 -3.483000e+02 +1 2928 1.339100e+02 -4.729000e+02 +6 2928 -5.319000e+01 -3.481700e+02 +1 2929 1.508000e+02 -4.723300e+02 +6 2929 -3.919000e+01 -3.484100e+02 +1 2930 1.480601e+02 -4.688500e+02 +6 2930 -4.153003e+01 -3.459000e+02 +1 2931 9.253501e+02 -4.669800e+02 +3 2931 9.745400e+02 -3.673900e+02 +1 2932 1.043300e+02 -4.588400e+02 +3 2932 5.701801e+02 -3.540000e+02 +1 2933 9.027002e+01 -4.553000e+02 +3 2933 5.517500e+02 -3.510400e+02 +1 2934 -5.808600e+02 -4.510400e+02 +6 2934 -2.585300e+02 -3.319900e+02 +1 2935 -1.037850e+03 -4.490400e+02 +6 2935 -6.315100e+02 -3.126600e+02 +1 2936 -8.861200e+02 -4.474200e+02 +6 2936 -5.134100e+02 -3.169000e+02 +1 2937 -8.307400e+02 -4.432800e+02 +6 2937 -4.672400e+02 -3.164100e+02 +1 2938 -1.143030e+03 -4.418400e+02 +6 2938 -7.092100e+02 -3.041100e+02 +1 2939 -7.405100e+02 -4.404200e+02 +3 2939 -7.310000e+02 -3.563700e+02 +1 2940 -8.244800e+02 -4.399000e+02 +3 2940 -8.039600e+02 -3.558700e+02 +1 2941 -8.469600e+02 -4.330500e+02 +6 2941 -4.801400e+02 -3.086200e+02 +1 2942 -8.916200e+02 -4.328400e+02 +3 2942 -8.620800e+02 -3.482000e+02 +6 2942 -5.174700e+02 -3.069100e+02 +1 2943 -8.916200e+02 -4.328400e+02 +3 2943 -8.620800e+02 -3.482000e+02 +1 2944 -9.795400e+02 -4.307300e+02 +6 2944 -5.866300e+02 -3.017000e+02 +1 2945 -8.353500e+02 -4.293700e+02 +3 2945 -8.140100e+02 -3.444399e+02 +1 2946 -8.893300e+02 -4.293600e+02 +3 2946 -8.601800e+02 -3.447800e+02 +1 2947 -1.046210e+03 -4.277400e+02 +3 2947 -1.010360e+03 -3.451400e+02 +1 2948 -8.342100e+02 -4.227200e+02 +3 2948 -8.128800e+02 -3.374301e+02 +1 2949 -8.483600e+02 -4.227000e+02 +6 2949 -4.808600e+02 -3.017400e+02 +1 2950 8.979299e+02 -4.219900e+02 +3 2950 9.459700e+02 -3.223800e+02 +1 2951 -9.690900e+02 -4.200500e+02 +6 2951 -5.779900e+02 -2.950900e+02 +1 2952 -9.954900e+02 -4.193600e+02 +6 2952 -5.979700e+02 -2.940300e+02 +1 2953 8.964600e+02 -4.189301e+02 +3 2953 9.455400e+02 -3.195900e+02 +1 2954 -8.280600e+02 -4.191899e+02 +3 2954 -8.078000e+02 -3.340400e+02 +6 2954 -4.635200e+02 -2.998500e+02 +1 2955 -8.280600e+02 -4.191899e+02 +3 2955 -8.078000e+02 -3.340400e+02 +1 2956 -9.006300e+02 -4.178800e+02 +3 2956 -8.687200e+02 -3.323800e+02 +1 2957 9.345996e+01 -4.143600e+02 +3 2957 5.555699e+02 -3.051000e+02 +1 2958 8.292004e+01 -4.010400e+02 +3 2958 5.457000e+02 -2.900601e+02 +1 2959 1.631899e+02 -3.958700e+02 +6 2959 -2.895001e+01 -2.916700e+02 +1 2960 -4.645601e+02 -3.848600e+02 +6 2960 -1.493600e+02 -2.915100e+02 +1 2961 1.148300e+02 -3.842100e+02 +3 2961 5.818900e+02 -2.711300e+02 +1 2962 7.363301e+02 -3.828500e+02 +3 2962 7.422200e+02 -2.859600e+02 +1 2963 -8.973900e+02 -3.829500e+02 +3 2963 -8.667600e+02 -2.954500e+02 +1 2964 -4.341300e+02 -3.801200e+02 +3 2964 -4.824900e+02 -2.927700e+02 +1 2965 -3.427100e+02 -3.750200e+02 +3 2965 -4.194300e+02 -2.890900e+02 +1 2966 -4.531000e+02 -3.735800e+02 +6 2966 -1.410500e+02 -2.843300e+02 +1 2967 -3.588700e+02 -3.603300e+02 +3 2967 -4.322000e+02 -2.734399e+02 +1 2968 5.168800e+02 -3.587200e+02 +3 2968 3.817500e+02 -2.683400e+02 +17 2968 -1.544320e+03 8.601001e+01 +1 2969 5.110601e+02 -3.589500e+02 +3 2969 3.766700e+02 -2.685100e+02 +17 2969 -1.551080e+03 8.597998e+01 +1 2970 5.110601e+02 -3.589500e+02 +3 2970 3.766700e+02 -2.685100e+02 +17 2970 -1.551080e+03 8.597998e+01 +1 2971 4.931100e+02 -3.561200e+02 +3 2971 3.608900e+02 -2.660800e+02 +17 2971 -1.572180e+03 8.919995e+01 +1 2972 4.931100e+02 -3.561200e+02 +3 2972 3.608900e+02 -2.660800e+02 +17 2972 -1.572180e+03 8.919995e+01 +1 2973 -6.253700e+02 -3.547700e+02 +6 2973 -2.930300e+02 -2.636200e+02 +1 2974 -6.253700e+02 -3.547700e+02 +6 2974 -2.930300e+02 -2.636200e+02 +1 2975 1.222400e+02 -3.539700e+02 +3 2975 5.930900e+02 -2.366801e+02 +1 2976 -1.068600e+02 -3.531100e+02 +2 2976 -5.615002e+01 -1.507500e+02 +1 2977 -7.945000e+02 -3.488500e+02 +3 2977 -7.791100e+02 -2.593700e+02 +1 2978 -1.232300e+02 -3.383800e+02 +3 2978 -2.808800e+02 -2.541400e+02 +1 2979 -1.371800e+03 -3.333400e+02 +6 2979 -8.680200e+02 -2.231300e+02 +1 2980 -3.652600e+02 -3.176300e+02 +3 2980 -4.363400e+02 -2.299700e+02 +1 2981 8.084199e+02 -3.038199e+02 +2 2981 6.501100e+02 -1.607600e+02 +3 2981 8.348000e+02 -2.049301e+02 +1 2982 -1.369900e+02 -3.026100e+02 +3 2982 -2.889600e+02 -2.196300e+02 +1 2983 -5.502100e+02 -2.968400e+02 +3 2983 -5.741000e+02 -2.063000e+02 +1 2984 -5.378700e+02 -2.950500e+02 +3 2984 -5.649700e+02 -2.050200e+02 +1 2985 7.720200e+02 -2.922400e+02 +2 2985 6.260601e+02 -1.501200e+02 +3 2985 7.765500e+02 -1.951700e+02 +1 2986 7.883899e+02 -2.865300e+02 +3 2986 7.983300e+02 -1.889301e+02 +1 2987 7.280100e+02 -2.855000e+02 +3 2987 7.330000e+02 -1.876300e+02 +1 2988 7.692300e+02 -2.851600e+02 +3 2988 7.737600e+02 -1.870100e+02 +1 2989 7.858501e+02 -2.839100e+02 +3 2989 7.910400e+02 -1.863400e+02 +1 2990 1.015060e+03 -2.808700e+02 +8 2990 8.387800e+02 -1.140400e+02 +1 2991 -9.235400e+02 -2.809500e+02 +3 2991 -8.925500e+02 -1.869301e+02 +1 2992 -1.584998e+01 -2.721500e+02 +6 2992 3.351801e+02 -2.419300e+02 +1 2993 8.817800e+02 -2.684900e+02 +3 2993 9.300601e+02 -1.674700e+02 +1 2994 8.763799e+02 -2.541899e+02 +3 2994 9.231400e+02 -1.532900e+02 +1 2995 1.598199e+02 -2.507500e+02 +3 2995 -1.840500e+02 -1.783200e+02 +6 2995 4.881400e+02 -2.348900e+02 +9 2995 -3.373999e+01 2.806500e+02 +13 2995 -6.601200e+02 2.855400e+02 +1 2996 9.341499e+02 -2.502700e+02 +6 2996 8.072100e+02 -2.274500e+02 +1 2997 3.168300e+02 -2.347300e+02 +2 2997 3.570001e+01 5.842999e+01 +3 2997 -4.297998e+01 -1.636900e+02 +11 2997 6.781899e+02 2.404800e+02 +13 2997 -2.440699e+02 3.413500e+02 +1 2998 5.465200e+02 -2.312500e+02 +2 2998 4.404500e+02 -7.059003e+01 +3 2998 4.086500e+02 -1.442800e+02 +17 2998 -1.515890e+03 2.268500e+02 +1 2999 7.701399e+02 -2.185300e+02 +6 2999 1.636300e+02 -1.376200e+02 +1 3000 -1.249200e+02 -2.169000e+02 +6 3000 1.710300e+02 -1.929800e+02 +1 3001 -5.499900e+02 -1.988000e+02 +6 3001 -2.242500e+02 -1.596700e+02 +1 3002 8.445200e+02 -1.889600e+02 +2 3002 6.725000e+02 -9.341998e+01 +1 3003 9.213000e+02 -1.848700e+02 +3 3003 9.711499e+02 -8.234998e+01 +8 3003 7.880500e+02 -3.334003e+01 +1 3004 9.253799e+02 -1.783400e+02 +3 3004 9.753000e+02 -7.585999e+01 +1 3005 1.074630e+03 -1.759000e+02 +6 3005 9.087200e+02 -1.760300e+02 +1 3006 3.185500e+02 -1.694100e+02 +2 3006 3.751001e+01 1.280700e+02 +3 3006 -4.137000e+01 -1.012000e+02 +9 3006 1.122800e+02 3.747300e+02 +11 3006 6.802000e+02 3.028700e+02 +13 3006 -2.358900e+02 5.191100e+02 +1 3007 -1.228500e+02 -1.689900e+02 +6 3007 1.735601e+02 -1.599700e+02 +1 3008 5.529199e+02 -1.659399e+02 +2 3008 4.477200e+02 -2.658002e+01 +3 3008 4.209200e+02 -7.789001e+01 +17 3008 -1.500880e+03 2.956799e+02 +1 3009 3.508800e+02 -1.613199e+02 +2 3009 7.146002e+01 1.356700e+02 +3 3009 -1.046997e+01 -9.453998e+01 +1 3010 3.309500e+02 -1.502700e+02 +2 3010 5.076001e+01 1.477100e+02 +3 3010 -2.921997e+01 -8.279999e+01 +11 3010 6.926899e+02 3.218200e+02 +13 3010 -2.010699e+02 5.719900e+02 +1 3011 3.309500e+02 -1.502700e+02 +2 3011 5.059998e+01 1.476500e+02 +11 3011 6.926899e+02 3.218200e+02 +13 3011 -2.010699e+02 5.719900e+02 +1 3012 -6.134500e+02 -1.499301e+02 +6 3012 -2.718400e+02 -1.238600e+02 +1 3013 -5.248400e+02 -1.376700e+02 +3 3013 -5.575800e+02 -4.063000e+01 +1 3014 3.337800e+02 -1.309700e+02 +2 3014 5.291998e+01 1.685700e+02 +13 3014 -1.935699e+02 6.260500e+02 +1 3015 2.910100e+02 -1.299500e+02 +2 3015 7.869995e+00 1.693300e+02 +3 3015 -6.806006e+01 -6.376001e+01 +13 3015 -3.090100e+02 6.308800e+02 +1 3016 4.886200e+02 -1.276700e+02 +2 3016 3.686300e+02 3.153003e+01 +1 3017 4.921000e+02 -1.244800e+02 +3 3017 2.992800e+02 -4.219000e+01 +1 3018 7.677500e+02 -1.204399e+02 +3 3018 7.725000e+02 -2.148999e+01 +6 3018 7.082900e+02 -1.329100e+02 +1 3019 -1.096330e+03 -1.167900e+02 +6 3019 -6.671100e+02 -8.281000e+01 +1 3020 -6.515002e+01 -1.086000e+02 +8 3020 5.892100e+02 9.091998e+01 +1 3021 7.825701e+02 -1.044301e+02 +3 3021 7.879200e+02 -5.049988e+00 +17 3021 -1.156570e+03 2.726699e+02 +1 3022 -6.573400e+02 -1.008900e+02 +6 3022 -3.084000e+02 -8.862000e+01 +1 3023 -1.207200e+02 -9.629004e+01 +3 3023 -2.884700e+02 -1.392999e+01 +13 3023 -9.718300e+02 3.552900e+02 +1 3024 7.683601e+02 -9.453003e+01 +3 3024 7.725300e+02 5.559998e+00 +1 3025 5.542000e+02 -8.629004e+01 +3 3025 4.212400e+02 9.199829e-01 +1 3026 8.574299e+02 -8.008997e+01 +3 3026 8.995400e+02 2.332001e+01 +6 3026 7.564700e+02 -1.015800e+02 +1 3027 8.893000e+02 -7.885999e+01 +3 3027 9.371599e+02 2.584998e+01 +17 3027 -1.042530e+03 2.731500e+02 +1 3028 8.961101e+02 -7.830005e+01 +6 3028 7.814500e+02 -1.003300e+02 +17 3028 -1.036040e+03 2.726899e+02 +1 3029 9.322300e+02 -7.156995e+01 +3 3029 9.872200e+02 3.260999e+01 +1 3030 9.070500e+02 -6.517004e+01 +3 3030 9.580000e+02 3.840002e+01 +1 3031 7.401299e+02 -6.496997e+01 +3 3031 7.458800e+02 3.538000e+01 +1 3032 7.649700e+02 -6.144995e+01 +2 3032 6.229900e+02 -1.135999e+01 +1 3033 -4.125601e+02 -6.064001e+01 +6 3033 -9.559003e+01 -7.054999e+01 +1 3034 -4.688000e+01 -5.487000e+01 +8 3034 6.083700e+02 1.444500e+02 +1 3035 8.416699e+02 -5.445996e+01 +3 3035 8.786100e+02 4.903998e+01 +17 3035 -1.088510e+03 3.002500e+02 +1 3036 9.318000e+02 -5.050000e+01 +3 3036 9.867900e+02 5.465002e+01 +1 3037 -2.721801e+02 -3.804004e+01 +6 3037 3.764001e+01 -6.271002e+01 +1 3038 8.578501e+02 -3.310999e+01 +3 3038 9.011700e+02 7.102002e+01 +1 3039 -6.554900e+02 -7.840027e+00 +3 3039 -6.716900e+02 9.715002e+01 +1 3040 -5.966100e+02 -2.419983e+00 +3 3040 -6.206700e+02 1.013200e+02 +1 3041 -3.695900e+02 4.250000e+00 +3 3041 -4.434800e+02 1.002100e+02 +13 3041 -1.225220e+03 3.923600e+02 +1 3042 -6.472500e+02 7.440002e+00 +3 3042 -6.624400e+02 1.128000e+02 +1 3043 -6.305700e+02 9.960022e+00 +3 3043 -6.466400e+02 1.155000e+02 +1 3044 -3.440200e+02 2.641992e+01 +6 3044 -3.295001e+01 -1.454999e+01 +8 3044 -8.047998e+01 1.551300e+02 +1 3045 -5.728500e+02 3.960999e+01 +3 3045 -5.979500e+02 1.447900e+02 +1 3046 -7.496500e+02 4.129004e+01 +3 3046 -7.484700e+02 1.524900e+02 +1 3047 -1.117080e+03 4.793994e+01 +3 3047 -1.090430e+03 1.685200e+02 +1 3048 -3.951500e+02 4.959009e+01 +6 3048 -7.609998e+01 2.989990e+00 +1 3049 -1.081980e+03 6.202002e+01 +2 3049 -3.458300e+02 1.373999e+01 +1 3050 8.106101e+02 6.514001e+01 +3 3050 8.357000e+02 1.691400e+02 +1 3051 -2.860200e+02 8.493994e+01 +3 3051 -3.901300e+02 1.782900e+02 +1 3052 -1.267600e+02 8.745996e+01 +8 3052 3.139600e+02 2.485300e+02 +11 3052 4.896000e+02 2.880700e+02 +1 3053 -4.818900e+02 8.759998e+01 +6 3053 -1.529800e+02 3.365997e+01 +1 3054 -4.818900e+02 8.759998e+01 +6 3054 -1.529800e+02 3.365997e+01 +1 3055 -3.089000e+02 9.230005e+01 +6 3055 4.650024e+00 2.860999e+01 +1 3056 -4.377900e+02 9.765991e+01 +6 3056 -1.186100e+02 3.932001e+01 +1 3057 8.769700e+02 1.163301e+02 +3 3057 9.239399e+02 2.232600e+02 +1 3058 7.651001e+02 1.181500e+02 +3 3058 7.718300e+02 2.211599e+02 +1 3059 8.882300e+02 1.203101e+02 +3 3059 9.366299e+02 2.276899e+02 +1 3060 9.706001e+02 1.223700e+02 +3 3060 1.029410e+03 2.301699e+02 +1 3061 -5.119100e+02 1.259099e+02 +3 3061 -5.501000e+02 2.329500e+02 +1 3062 9.629099e+02 1.284900e+02 +3 3062 1.019860e+03 2.366100e+02 +1 3063 1.215930e+03 1.322200e+02 +8 3063 1.004000e+03 2.333800e+02 +1 3064 9.643501e+02 1.324299e+02 +3 3064 1.022060e+03 2.405300e+02 +1 3065 1.044640e+03 1.402800e+02 +3 3065 1.108820e+03 2.488101e+02 +1 3066 1.210260e+03 1.450000e+02 +6 3066 1.018560e+03 6.178998e+01 +1 3067 -2.061300e+02 1.625300e+02 +6 3067 1.492700e+02 6.425000e+01 +8 3067 2.474600e+02 3.170100e+02 +13 3067 -1.192650e+03 9.172400e+02 +1 3068 -2.061300e+02 1.625300e+02 +6 3068 1.492700e+02 6.425000e+01 +13 3068 -1.192650e+03 9.172400e+02 +1 3069 8.825901e+02 1.741899e+02 +3 3069 9.344600e+02 2.832100e+02 +1 3070 -3.631300e+02 1.777300e+02 +3 3070 -4.388700e+02 2.790000e+02 +8 3070 -1.105000e+02 2.826200e+02 +13 3070 -1.212380e+03 6.770000e+02 +1 3071 -7.116700e+02 1.800901e+02 +6 3071 -3.470700e+02 1.070300e+02 +1 3072 -7.116700e+02 1.800901e+02 +6 3072 -3.470700e+02 1.070300e+02 +1 3073 -3.658700e+02 1.804099e+02 +3 3073 -4.412400e+02 2.818000e+02 +13 3073 -1.216930e+03 6.813900e+02 +1 3074 -9.915000e+02 1.900801e+02 +3 3074 -9.697700e+02 3.192800e+02 +1 3075 8.982900e+02 2.442700e+02 +3 3075 9.479800e+02 3.540400e+02 +1 3076 8.982900e+02 2.442700e+02 +3 3076 9.479800e+02 3.540400e+02 +1 3077 1.095020e+03 2.499000e+02 +6 3077 9.349900e+02 1.409800e+02 +1 3078 -2.081600e+02 2.534299e+02 +2 3078 -1.885400e+02 3.420500e+02 +8 3078 2.474301e+02 4.013500e+02 +13 3078 -1.198240e+03 1.105600e+03 +1 3079 -2.081600e+02 2.534299e+02 +2 3079 -1.885400e+02 3.420500e+02 +8 3079 2.474301e+02 4.013500e+02 +13 3079 -1.198240e+03 1.105600e+03 +1 3080 -2.081200e+02 2.620400e+02 +2 3080 -1.885900e+02 3.487400e+02 +9 3080 -1.847300e+02 4.797200e+02 +13 3080 -1.198100e+03 1.122990e+03 +1 3081 -2.081200e+02 2.620400e+02 +2 3081 -1.885900e+02 3.487400e+02 +13 3081 -1.198100e+03 1.122990e+03 +1 3082 1.047850e+03 2.662900e+02 +3 3082 1.112350e+03 3.773201e+02 +1 3083 9.400200e+02 2.727100e+02 +3 3083 9.935500e+02 3.838600e+02 +1 3084 7.377600e+02 2.742000e+02 +6 3084 6.949000e+02 1.540000e+02 +1 3085 8.815100e+02 2.745901e+02 +2 3085 6.975800e+02 1.678000e+02 +3 3085 9.284700e+02 3.849800e+02 +17 3085 -1.045880e+03 5.838301e+02 +1 3086 7.682400e+02 2.748000e+02 +3 3086 7.734700e+02 3.804399e+02 +1 3087 5.675100e+02 2.803101e+02 +3 3087 5.454399e+02 3.836400e+02 +1 3088 1.065710e+03 2.868301e+02 +8 3088 8.926300e+02 3.645601e+02 +1 3089 9.612600e+02 2.907900e+02 +3 3089 1.018920e+03 4.023300e+02 +1 3090 9.110801e+02 3.108600e+02 +6 3090 8.007100e+02 1.847900e+02 +1 3091 9.016699e+02 3.167300e+02 +3 3091 9.524900e+02 4.285000e+02 +1 3092 9.589399e+02 3.194600e+02 +3 3092 1.015860e+03 4.319299e+02 +17 3092 -9.750900e+02 6.121799e+02 +1 3093 8.138601e+02 3.253401e+02 +3 3093 8.497100e+02 4.365000e+02 +1 3094 9.562300e+02 3.264000e+02 +3 3094 1.013390e+03 4.383400e+02 +17 3094 -9.773000e+02 6.187400e+02 +1 3095 1.048830e+03 3.376200e+02 +6 3095 9.006300e+02 2.055200e+02 +1 3096 1.053160e+03 3.396599e+02 +6 3096 9.036700e+02 2.071000e+02 +17 3096 -8.935400e+02 6.211400e+02 +1 3097 -4.120200e+02 3.623600e+02 +3 3097 -4.730400e+02 4.734200e+02 +1 3098 8.782500e+02 3.641699e+02 +3 3098 9.245400e+02 4.764800e+02 +1 3099 -5.729400e+02 3.704000e+02 +6 3099 -1.740200e+02 2.226100e+02 +1 3100 8.880000e+02 3.746300e+02 +3 3100 9.365200e+02 4.880200e+02 +1 3101 1.022240e+03 3.794000e+02 +3 3101 1.088230e+03 4.931100e+02 +1 3102 -1.173600e+03 3.954399e+02 +6 3102 -7.078100e+02 2.683300e+02 +1 3103 -4.751000e+02 4.041400e+02 +6 3103 -1.354200e+02 2.500100e+02 +1 3104 -4.641801e+02 4.075300e+02 +3 3104 -5.238500e+02 5.229299e+02 +1 3105 -8.978700e+02 4.378500e+02 +3 3105 -8.789000e+02 5.850800e+02 +1 3106 1.013610e+03 4.401100e+02 +8 3106 8.528900e+02 4.935500e+02 +1 3107 -9.088300e+02 4.411000e+02 +3 3107 -8.894700e+02 5.890200e+02 +1 3108 1.034570e+03 4.602300e+02 +3 3108 1.027070e+03 5.656700e+02 +1 3109 9.834099e+02 4.605300e+02 +3 3109 9.862500e+02 5.665701e+02 +1 3110 -6.208900e+02 4.670300e+02 +3 3110 -6.925600e+02 5.849800e+02 +1 3111 -9.988800e+02 4.671400e+02 +3 3111 -9.784300e+02 6.210000e+02 +1 3112 -6.123300e+02 4.714000e+02 +3 3112 -6.829400e+02 5.897800e+02 +13 3112 -1.577640e+03 1.126830e+03 +1 3113 -6.189300e+02 4.735300e+02 +3 3113 -6.903600e+02 5.915100e+02 +1 3114 7.074600e+02 5.036300e+02 +3 3114 6.029600e+02 5.933900e+02 +1 3115 7.038899e+02 5.059200e+02 +3 3115 5.977400e+02 5.951300e+02 +1 3116 -7.964800e+02 5.275200e+02 +3 3116 -7.972800e+02 6.737500e+02 +1 3117 8.050901e+02 5.312600e+02 +3 3117 7.000800e+02 6.205601e+02 +1 3118 8.050901e+02 5.312600e+02 +3 3118 7.000800e+02 6.205601e+02 +1 3119 8.479900e+02 5.371200e+02 +6 3119 8.429700e+02 3.302300e+02 +1 3120 6.941799e+02 5.403800e+02 +3 3120 5.811200e+02 6.291200e+02 +17 3120 -1.322400e+03 1.041480e+03 +1 3121 7.696499e+02 5.658500e+02 +3 3121 6.618199e+02 6.557500e+02 +1 3122 7.665000e+02 5.672400e+02 +3 3122 6.582000e+02 6.564800e+02 +6 3122 7.833400e+02 3.515400e+02 +1 3123 -1.368570e+03 6.307900e+02 +6 3123 -8.349400e+02 4.307700e+02 +1 3124 -1.252370e+03 8.860900e+02 +6 3124 -7.490400e+02 6.038000e+02 +1 3125 1.422900e+02 -7.554500e+02 +3 3125 6.229500e+02 -6.818700e+02 +6 3125 -6.278003e+01 -5.616100e+02 +1 3126 1.646899e+02 -6.848300e+02 +3 3126 6.466500e+02 -6.037000e+02 +1 3127 5.754004e+01 -6.051300e+02 +3 3127 5.167100e+02 -5.175800e+02 +1 3128 1.410601e+02 -5.700100e+02 +3 3128 6.116500e+02 -4.768400e+02 +1 3129 -1.064610e+03 -5.635000e+02 +3 3129 -1.024210e+03 -4.883400e+02 +1 3130 -9.650400e+02 -5.631500e+02 +3 3130 -9.270000e+02 -4.870400e+02 +1 3131 -9.491300e+02 -5.600300e+02 +3 3131 -9.115500e+02 -4.838400e+02 +1 3132 1.152300e+02 -5.533900e+02 +3 3132 5.844200e+02 -4.590200e+02 +1 3133 1.073900e+02 -5.446100e+02 +6 3133 -7.670001e+01 -4.015400e+02 +1 3134 1.073900e+02 -5.446100e+02 +3 3134 5.748500e+02 -4.491700e+02 +1 3135 1.446600e+02 -5.391100e+02 +3 3135 6.156899e+02 -4.427300e+02 +1 3136 1.364700e+02 -5.272300e+02 +3 3136 6.075400e+02 -4.293700e+02 +1 3137 1.365601e+02 -5.242800e+02 +3 3137 6.077500e+02 -4.263500e+02 +1 3138 1.365601e+02 -5.242800e+02 +3 3138 6.077500e+02 -4.263500e+02 +1 3139 9.518994e+01 -4.996000e+02 +3 3139 5.592300e+02 -3.994000e+02 +1 3140 9.970996e+01 -4.990000e+02 +3 3140 5.651000e+02 -3.988600e+02 +1 3141 1.057800e+02 -4.736899e+02 +3 3141 5.712400e+02 -3.708400e+02 +1 3142 -8.900100e+02 -4.482000e+02 +3 3142 -8.603000e+02 -3.643700e+02 +1 3143 -8.900100e+02 -4.482000e+02 +3 3143 -8.603000e+02 -3.643700e+02 +1 3144 9.182996e+01 -4.214200e+02 +3 3144 5.544301e+02 -3.128800e+02 +1 3145 8.404004e+01 -4.113300e+02 +3 3145 5.442500e+02 -3.024301e+02 +1 3146 1.124500e+02 -3.966400e+02 +3 3146 5.819500e+02 -2.845200e+02 +1 3147 7.407400e+02 -3.856700e+02 +3 3147 7.455300e+02 -2.885400e+02 +1 3148 -1.098800e+02 -3.697700e+02 +3 3148 -2.701700e+02 -2.853400e+02 +1 3149 -9.803003e+01 -3.495000e+02 +8 3149 2.849800e+02 -1.569200e+02 +1 3150 -7.926200e+02 -3.455100e+02 +3 3150 -7.770600e+02 -2.560000e+02 +1 3151 -1.105100e+02 -3.011500e+02 +3 3151 -2.706700e+02 -2.175500e+02 +1 3152 7.758997e+01 -2.917600e+02 +3 3152 -2.274500e+02 -2.163700e+02 +13 3152 -8.053600e+02 1.215300e+02 +1 3153 7.715701e+02 -2.803101e+02 +3 3153 7.763700e+02 -1.822600e+02 +1 3154 -9.265200e+02 -2.772400e+02 +3 3154 -8.955300e+02 -1.829500e+02 +1 3155 -1.119980e+03 -2.730400e+02 +3 3155 -1.085000e+03 -1.783400e+02 +1 3156 -1.119980e+03 -2.730400e+02 +3 3156 -1.085000e+03 -1.783400e+02 +1 3157 3.603101e+02 -2.671000e+02 +2 3157 8.834998e+01 2.121997e+01 +3 3157 3.150024e+00 -1.937200e+02 +11 3157 7.243500e+02 2.047600e+02 +13 3157 -1.239301e+02 2.425601e+02 +1 3158 5.469800e+02 -2.502900e+02 +2 3158 4.407000e+02 -8.206000e+01 +3 3158 4.092700e+02 -1.597300e+02 +17 3158 -1.515520e+03 2.096500e+02 +1 3159 3.258000e+02 -2.417900e+02 +2 3159 4.478998e+01 5.128998e+01 +13 3159 -2.197500e+02 3.202300e+02 +1 3160 8.405200e+02 -1.895300e+02 +3 3160 8.719301e+02 -8.744000e+01 +1 3161 2.711300e+02 -1.840699e+02 +2 3161 -1.320001e+01 1.126400e+02 +3 3161 -8.691003e+01 -1.149000e+02 +13 3161 -3.672500e+02 4.812400e+02 +1 3162 3.521500e+02 -1.825500e+02 +2 3162 7.210999e+01 1.142700e+02 +3 3162 -9.880005e+00 -1.135500e+02 +9 3162 1.450500e+02 3.626200e+02 +13 3162 -1.451400e+02 4.832400e+02 +1 3163 -4.088900e+02 -1.748199e+02 +8 3163 -1.632900e+02 -1.763000e+01 +1 3164 3.485601e+02 -1.732600e+02 +2 3164 6.790997e+01 1.252100e+02 +9 3164 1.412300e+02 3.720200e+02 +1 3165 5.525400e+02 -1.401801e+02 +3 3165 4.196801e+02 -5.259998e+01 +1 3166 -1.545996e+01 -1.387400e+02 +8 3166 6.392400e+02 6.159998e+01 +1 3167 1.156210e+03 -1.260900e+02 +8 3167 9.541000e+02 1.558002e+01 +1 3168 5.603000e+02 -1.239399e+02 +3 3168 4.283000e+02 -3.602002e+01 +17 3168 -1.492800e+03 3.412700e+02 +1 3169 -8.279200e+02 -1.179000e+02 +3 3169 -8.128300e+02 -1.446997e+01 +13 3169 -1.682400e+03 9.650000e+01 +1 3170 3.196300e+02 -1.168300e+02 +2 3170 3.839001e+01 1.829700e+02 +3 3170 -4.062000e+01 -5.103003e+01 +13 3170 -2.313400e+02 6.631300e+02 +1 3171 -3.676500e+02 -1.100601e+02 +8 3171 -1.111500e+02 3.932001e+01 +1 3172 3.197700e+02 -1.061000e+02 +2 3172 3.857001e+01 1.951900e+02 +13 3172 -2.295800e+02 6.968400e+02 +1 3173 7.675100e+02 -1.025699e+02 +3 3173 7.722300e+02 -3.210022e+00 +1 3174 -5.326100e+02 -1.160999e+01 +3 3174 -5.625100e+02 9.032001e+01 +1 3175 -9.412000e+01 1.071002e+01 +3 3175 -2.853800e+02 9.090997e+01 +13 3175 -9.595300e+02 5.961500e+02 +1 3176 -3.165300e+02 3.640991e+01 +6 3176 -3.280029e+00 -9.270020e+00 +1 3177 -1.210900e+02 7.153003e+01 +3 3177 -3.139600e+02 1.509800e+02 +13 3177 -1.015570e+03 7.214700e+02 +1 3178 -1.267600e+02 7.535999e+01 +3 3178 -3.207600e+02 1.547400e+02 +1 3179 8.765601e+02 1.029700e+02 +3 3179 9.255400e+02 2.099800e+02 +1 3180 8.761499e+02 1.061200e+02 +3 3180 9.252500e+02 2.135500e+02 +1 3181 8.761499e+02 1.061200e+02 +3 3181 9.252500e+02 2.135500e+02 +17 3181 -1.051840e+03 4.339700e+02 +1 3182 1.027530e+03 1.230601e+02 +3 3182 1.093050e+03 2.314199e+02 +1 3183 1.039440e+03 1.295400e+02 +3 3183 1.103520e+03 2.377600e+02 +1 3184 1.230260e+03 1.383301e+02 +8 3184 1.019260e+03 2.386600e+02 +1 3185 -1.937100e+02 1.609600e+02 +8 3185 2.594399e+02 3.160800e+02 +13 3185 -1.169300e+03 9.139900e+02 +1 3186 -3.639301e+02 1.745601e+02 +3 3186 -4.393600e+02 2.757500e+02 +13 3186 -1.214700e+03 6.723900e+02 +1 3187 8.739099e+02 2.228800e+02 +3 3187 9.210300e+02 3.322900e+02 +1 3188 7.454900e+02 2.272700e+02 +3 3188 7.494500e+02 3.317400e+02 +1 3189 -6.637700e+02 2.412900e+02 +3 3189 -6.794500e+02 3.613101e+02 +1 3190 -2.054900e+02 2.417900e+02 +2 3190 -1.859700e+02 3.329100e+02 +8 3190 2.501100e+02 3.909200e+02 +1 3191 -1.270030e+03 2.472300e+02 +8 3191 -9.911500e+02 2.720500e+02 +1 3192 9.173000e+02 2.632400e+02 +3 3192 9.676499e+02 3.735800e+02 +1 3193 9.620801e+02 2.734700e+02 +3 3193 1.019870e+03 3.848300e+02 +1 3194 9.848501e+02 2.769399e+02 +3 3194 1.044880e+03 3.880100e+02 +1 3195 -4.419301e+02 3.964900e+02 +3 3195 -5.037300e+02 5.110000e+02 +1 3196 -6.974800e+02 3.994399e+02 +3 3196 -7.108900e+02 5.292900e+02 +13 3196 -1.562680e+03 8.813800e+02 +1 3197 -5.956700e+02 4.253000e+02 +3 3197 -6.639400e+02 5.414399e+02 +1 3198 -1.018910e+03 4.533500e+02 +3 3198 -9.996400e+02 6.063600e+02 +1 3199 -6.116600e+02 4.565100e+02 +3 3199 -6.818700e+02 5.738101e+02 +1 3200 -9.841100e+02 4.563401e+02 +3 3200 -9.633800e+02 6.089200e+02 +1 3201 -6.284600e+02 4.687900e+02 +3 3201 -7.005300e+02 5.870701e+02 +1 3202 -6.284600e+02 4.687900e+02 +3 3202 -7.005300e+02 5.870701e+02 +1 3203 9.518999e+02 5.178300e+02 +3 3203 8.428900e+02 6.042900e+02 +2 3204 -4.947800e+02 -6.950012e+00 +7 3204 1.080000e+02 2.776599e+02 +9 3204 -4.851300e+02 1.300801e+02 +2 3205 -4.944400e+02 1.148700e+02 +7 3205 1.073500e+02 3.476699e+02 +10 3205 -3.599600e+02 -3.796801e+02 +11 3205 1.753300e+02 1.568400e+02 +12 3205 -9.988200e+02 -4.927600e+02 +2 3206 -4.944400e+02 1.148700e+02 +7 3206 1.073500e+02 3.476699e+02 +9 3206 -4.844700e+02 2.214000e+02 +11 3206 1.753300e+02 1.568400e+02 +2 3207 -4.197300e+02 1.465700e+02 +7 3207 1.524800e+02 3.670000e+02 +10 3207 -3.204100e+02 -3.615200e+02 +11 3207 2.288500e+02 1.802300e+02 +12 3207 -9.544400e+02 -4.719200e+02 +18 3207 -5.400200e+02 3.987000e+01 +2 3208 -4.197300e+02 1.465700e+02 +4 3208 8.060200e+02 3.414099e+02 +7 3208 1.524800e+02 3.670000e+02 +9 3208 -4.296000e+02 2.469800e+02 +11 3208 2.288500e+02 1.802300e+02 +18 3208 -5.400200e+02 3.987000e+01 +20 3208 -4.605800e+02 -1.656801e+02 +2 3209 -5.033200e+02 2.939400e+02 +7 3209 9.467004e+01 4.553301e+02 +9 3209 -4.927400e+02 3.551300e+02 +10 3209 -3.629700e+02 -2.812200e+02 +2 3210 -6.189400e+02 2.954500e+02 +7 3210 4.104004e+01 4.528000e+02 +9 3210 -5.823200e+02 3.547300e+02 +2 3211 7.303101e+02 -5.197998e+01 +3 3211 9.977400e+02 2.359985e+00 +2 3212 -5.568700e+02 3.900146e-01 +7 3212 7.070996e+01 2.766599e+02 +9 3212 -5.315000e+02 1.287100e+02 +16 3212 2.915200e+02 2.967900e+02 +2 3213 7.660500e+02 -2.208002e+01 +3 3213 1.065940e+03 5.934003e+01 +2 3214 4.365400e+02 -1.940002e+00 +3 3214 4.021100e+02 -5.096997e+01 +11 3214 9.339500e+02 1.165800e+02 +17 3214 -1.525450e+03 3.381300e+02 +2 3215 -3.618200e+02 2.309700e+02 +7 3215 1.853000e+02 4.206000e+02 +9 3215 -3.795800e+02 3.106500e+02 +10 3215 -2.864900e+02 -3.171000e+02 +11 3215 2.716300e+02 2.444900e+02 +12 3215 -9.175600e+02 -4.232100e+02 +2 3216 -5.041300e+02 2.371700e+02 +7 3216 1.009399e+02 4.195000e+02 +9 3216 -4.935200e+02 3.133101e+02 +10 3216 -3.664301e+02 -3.141200e+02 +11 3216 1.677200e+02 2.451200e+02 +16 3216 3.129301e+02 4.044100e+02 +2 3217 -6.595200e+02 4.186500e+02 +7 3217 1.309998e+01 5.248800e+02 +9 3217 -6.118500e+02 4.515200e+02 +10 3217 -4.482900e+02 -2.164200e+02 +11 3217 5.344995e+01 3.780200e+02 +12 3217 -1.093350e+03 -3.067200e+02 +16 3217 2.452700e+02 4.822400e+02 +18 3217 -6.529400e+02 1.699199e+02 +2 3218 -5.727600e+02 4.318300e+02 +7 3218 6.793994e+01 5.330601e+02 +9 3218 -5.404500e+02 4.587900e+02 +10 3218 -3.984399e+02 -2.092800e+02 +16 3218 2.872800e+02 4.900400e+02 +2 3219 -2.845500e+02 1.312000e+01 +3 3219 -9.047500e+02 1.722800e+02 +4 3219 8.885601e+02 2.837500e+02 +5 3219 4.567400e+02 6.495300e+02 +7 3219 2.434900e+02 2.908700e+02 +9 3219 -3.186500e+02 1.489600e+02 +10 3219 -2.422400e+02 -4.311600e+02 +11 3219 3.296400e+02 9.076001e+01 +12 3219 -8.684900e+02 -5.469500e+02 +18 3219 -4.735200e+02 -2.395996e+01 +20 3219 -4.013199e+02 -2.187900e+02 +2 3220 -5.189500e+02 1.701001e+01 +7 3220 9.045996e+01 2.886599e+02 +16 3220 3.063000e+02 3.040500e+02 +2 3221 -1.518200e+02 1.149100e+02 +7 3221 3.705100e+02 3.527600e+02 +9 3221 -2.023800e+02 2.438900e+02 +10 3221 -1.500200e+02 -3.756600e+02 +11 3221 4.359900e+02 1.810200e+02 +12 3221 -7.534700e+02 -4.779500e+02 +18 3221 -3.965800e+02 3.371997e+01 +20 3221 -3.354500e+02 -1.688800e+02 +2 3222 -3.126100e+02 1.243600e+02 +7 3222 2.235100e+02 3.533900e+02 +9 3222 -3.432500e+02 2.409099e+02 +10 3222 -2.590800e+02 -3.740200e+02 +11 3222 3.083500e+02 1.722800e+02 +12 3222 -8.857500e+02 -4.858800e+02 +18 3222 -4.875800e+02 3.071997e+01 +2 3223 -4.927800e+02 1.904300e+02 +7 3223 1.063600e+02 3.926500e+02 +9 3223 -4.812400e+02 2.773000e+02 +11 3223 1.744500e+02 2.115000e+02 +18 3223 -5.773300e+02 5.852002e+01 +2 3224 -1.624600e+02 2.239800e+02 +7 3224 3.580699e+02 4.192300e+02 +9 3224 -2.143800e+02 3.272700e+02 +10 3224 -1.578500e+02 -3.160699e+02 +12 3224 -7.614600e+02 -4.116700e+02 +13 3224 -1.387370e+03 8.203400e+02 +20 3224 -3.405699e+02 -1.238900e+02 +2 3225 -3.405400e+02 2.602900e+02 +7 3225 2.007400e+02 4.344500e+02 +9 3225 -3.690000e+02 3.360801e+02 +10 3225 -2.756100e+02 -2.989301e+02 +11 3225 2.850699e+02 2.666700e+02 +12 3225 -9.023400e+02 -4.030900e+02 +18 3225 -5.012400e+02 9.223999e+01 +20 3225 -4.255699e+02 -1.189600e+02 +2 3226 -5.192100e+02 2.686400e+02 +7 3226 9.156995e+01 4.375100e+02 +10 3226 -3.758199e+02 -2.961801e+02 +16 3226 3.058700e+02 4.185800e+02 +2 3227 -5.190700e+02 2.964300e+02 +7 3227 9.271997e+01 4.557200e+02 +10 3227 -3.754000e+02 -2.815300e+02 +16 3227 3.061801e+02 4.324100e+02 +2 3228 -4.680900e+02 3.616900e+02 +7 3228 1.223000e+02 4.954299e+02 +9 3228 -4.672300e+02 4.077100e+02 +10 3228 -3.476000e+02 -2.458000e+02 +11 3228 1.917900e+02 3.372500e+02 +16 3228 3.267200e+02 4.626500e+02 +18 3228 -5.639700e+02 1.416400e+02 +2 3229 -5.123400e+02 4.129100e+02 +7 3229 9.607996e+01 5.265000e+02 +9 3229 -5.015100e+02 4.478800e+02 +10 3229 -3.706200e+02 -2.172000e+02 +11 3229 1.589000e+02 3.761100e+02 +12 3229 -1.007020e+03 -3.141801e+02 +16 3229 3.083199e+02 4.864100e+02 +2 3230 -5.123400e+02 4.129100e+02 +5 3230 2.502400e+02 8.701100e+02 +7 3230 9.607996e+01 5.265000e+02 +9 3230 -5.015100e+02 4.478800e+02 +10 3230 -3.706200e+02 -2.172000e+02 +11 3230 1.589000e+02 3.761100e+02 +16 3230 3.083199e+02 4.864100e+02 +2 3231 -6.063100e+02 4.351100e+02 +7 3231 4.293994e+01 5.366400e+02 +9 3231 -5.728900e+02 4.646500e+02 +10 3231 -4.206500e+02 -2.071000e+02 +12 3231 -1.063660e+03 -2.996500e+02 +16 3231 2.669800e+02 4.927400e+02 +18 3231 -6.268500e+02 1.756200e+02 +2 3232 5.119900e+02 -3.602000e+02 +7 3232 4.496997e+01 7.640991e+01 +12 3232 -8.543700e+02 -8.360601e+02 +2 3233 -3.448300e+02 -1.698600e+02 +7 3233 1.979800e+02 1.793000e+02 +9 3233 -3.666300e+02 7.680054e+00 +11 3233 2.847100e+02 -4.690002e+01 +12 3233 -9.155100e+02 -6.632400e+02 +20 3233 -4.300800e+02 -2.948700e+02 +2 3234 -4.284000e+02 -1.058000e+02 +7 3234 1.445400e+02 2.178301e+02 +2 3235 -4.844000e+02 -1.052200e+02 +7 3235 1.098199e+02 2.183600e+02 +9 3235 -4.739700e+02 5.435999e+01 +10 3235 -3.570200e+02 -4.987200e+02 +12 3235 -1.003020e+03 -6.244399e+02 +2 3236 4.313700e+02 -5.763000e+01 +3 3236 3.867500e+02 -1.335500e+02 +11 3236 9.328101e+02 7.160999e+01 +17 3236 -1.542290e+03 2.460300e+02 +2 3237 -5.044800e+02 -4.337000e+01 +7 3237 9.830005e+01 2.545300e+02 +9 3237 -4.898800e+02 1.004600e+02 +10 3237 -3.685699e+02 -4.647200e+02 +11 3237 1.666899e+02 4.252002e+01 +12 3237 -1.015260e+03 -5.870300e+02 +16 3237 3.123700e+02 2.783800e+02 +18 3237 -5.847900e+02 -5.093994e+01 +20 3237 -4.969200e+02 -2.434399e+02 +2 3238 -4.182600e+02 -1.433002e+01 +4 3238 8.029500e+02 2.671100e+02 +7 3238 1.528199e+02 2.715100e+02 +9 3238 -4.258900e+02 1.236100e+02 +10 3238 -3.203600e+02 -4.474399e+02 +12 3238 -9.584700e+02 -5.691899e+02 +20 3238 -4.608400e+02 -2.327500e+02 +2 3239 -5.004000e+02 -3.940002e+00 +7 3239 1.010400e+02 2.769900e+02 +9 3239 -4.861300e+02 1.306300e+02 +10 3239 -3.665500e+02 -4.436600e+02 +11 3239 1.702200e+02 7.123999e+01 +12 3239 -1.011650e+03 -5.644600e+02 +16 3239 3.149900e+02 2.951700e+02 +18 3239 -5.816400e+02 -3.401001e+01 +2 3240 -4.738900e+02 1.531000e+01 +7 3240 1.189900e+02 2.889399e+02 +10 3240 -3.527400e+02 -4.324200e+02 +11 3240 1.885601e+02 8.494000e+01 +12 3240 -9.962600e+02 -5.510601e+02 +16 3240 3.282500e+02 3.050800e+02 +2 3241 -2.829100e+02 4.620001e+01 +7 3241 2.443300e+02 3.068201e+02 +9 3241 -3.177000e+02 1.768401e+02 +2 3242 -2.384500e+02 1.313300e+02 +7 3242 2.879100e+02 3.554299e+02 +9 3242 -2.790601e+02 2.422600e+02 +10 3242 -2.097300e+02 -3.709700e+02 +11 3242 3.660601e+02 1.806300e+02 +12 3242 -8.270000e+02 -4.792100e+02 +18 3242 -4.462300e+02 3.456995e+01 +2 3243 -3.137400e+02 1.695500e+02 +7 3243 2.230800e+02 3.797500e+02 +9 3243 -3.432500e+02 2.682600e+02 +10 3243 -2.595200e+02 -3.511500e+02 +11 3243 3.084500e+02 2.018800e+02 +12 3243 -8.844800e+02 -4.596600e+02 +18 3243 -4.877600e+02 5.018994e+01 +2 3244 -4.770200e+02 1.693100e+02 +7 3244 1.171100e+02 3.801000e+02 +2 3245 -4.476600e+02 1.827700e+02 +7 3245 1.343900e+02 3.877600e+02 +11 3245 2.075300e+02 2.072300e+02 +12 3245 -9.742400e+02 -4.498101e+02 +2 3246 -2.587100e+02 1.931600e+02 +7 3246 2.675800e+02 3.959399e+02 +10 3246 -2.245300e+02 -3.359600e+02 +11 3246 3.493000e+02 2.246300e+02 +12 3246 -8.441900e+02 -4.414600e+02 +18 3246 -4.588199e+02 6.309998e+01 +2 3247 -2.587100e+02 1.931600e+02 +7 3247 2.675800e+02 3.959399e+02 +10 3247 -2.245300e+02 -3.359600e+02 +12 3247 -8.441900e+02 -4.414600e+02 +2 3248 -5.449800e+02 2.870000e+02 +7 3248 7.756006e+01 4.508600e+02 +9 3248 -5.254700e+02 3.504299e+02 +10 3248 -3.884399e+02 -2.867000e+02 +2 3249 -3.416600e+02 3.114000e+02 +7 3249 2.020500e+02 4.696599e+02 +10 3249 -2.775800e+02 -2.702800e+02 +11 3249 2.836200e+02 3.075700e+02 +18 3249 -5.019000e+02 1.182900e+02 +2 3250 -5.599100e+02 3.097300e+02 +7 3250 6.882996e+01 4.631000e+02 +10 3250 -3.974301e+02 -2.738600e+02 +16 3250 2.882100e+02 4.369200e+02 +2 3251 -5.457000e+02 3.283600e+02 +7 3251 7.731006e+01 4.747800e+02 +10 3251 -3.890699e+02 -2.640601e+02 +16 3251 2.944500e+02 4.461600e+02 +2 3252 -4.382100e+02 3.592200e+02 +7 3252 1.391100e+02 4.941799e+02 +9 3252 -4.431300e+02 4.071400e+02 +2 3253 -6.027900e+02 4.038100e+02 +5 3253 2.024000e+02 8.476600e+02 +7 3253 4.427002e+01 5.171699e+02 +9 3253 -5.694400e+02 4.387200e+02 +10 3253 -4.193500e+02 -2.242600e+02 +12 3253 -1.062620e+03 -3.196600e+02 +16 3253 2.685601e+02 4.774500e+02 +18 3253 -6.262900e+02 1.587000e+02 +2 3254 -6.875700e+02 4.283000e+02 +5 3254 1.597000e+02 8.538500e+02 +7 3254 -2.660034e+00 5.318700e+02 +9 3254 -6.344900e+02 4.573401e+02 +11 3254 3.281995e+01 3.831500e+02 +14 3254 4.545400e+02 3.402400e+02 +2 3255 -4.922900e+02 -2.714001e+01 +7 3255 1.056400e+02 2.635801e+02 +9 3255 -4.809900e+02 1.127400e+02 +10 3255 -3.620400e+02 -4.559200e+02 +11 3255 1.763500e+02 5.403998e+01 +12 3255 -1.007980e+03 -5.774600e+02 +16 3255 3.183500e+02 2.852100e+02 +18 3255 -5.787900e+02 -4.458997e+01 +20 3255 -4.919200e+02 -2.371300e+02 +2 3256 -1.997400e+02 -2.150000e+01 +7 3256 3.210601e+02 2.675400e+02 +9 3256 -2.452800e+02 1.306300e+02 +11 3256 3.977300e+02 7.112000e+01 +13 3256 -1.516570e+03 2.110601e+02 +18 3256 -4.255100e+02 -3.573999e+01 +20 3256 -3.602400e+02 -2.289000e+02 +2 3257 9.750000e+01 -7.600098e-01 +7 3257 7.525601e+02 2.867600e+02 +2 3258 -4.365300e+02 3.733002e+01 +7 3258 1.417300e+02 3.011500e+02 +10 3258 -3.304700e+02 -4.214600e+02 +11 3258 2.161200e+02 1.021400e+02 +18 3258 -5.496500e+02 -1.355005e+01 +2 3259 -4.365300e+02 3.733002e+01 +7 3259 1.417300e+02 3.011500e+02 +9 3259 -4.397500e+02 1.619000e+02 +10 3259 -3.304700e+02 -4.214600e+02 +11 3259 2.161200e+02 1.021400e+02 +12 3259 -9.695000e+02 -5.377000e+02 +18 3259 -5.496500e+02 -1.355005e+01 +2 3260 6.867000e+02 4.495001e+01 +3 3260 9.089000e+02 1.641800e+02 +17 3260 -1.063570e+03 3.951300e+02 +2 3261 -4.013000e+02 8.490997e+01 +4 3261 8.128501e+02 3.124700e+02 +5 3261 3.514900e+02 6.751500e+02 +7 3261 1.670400e+02 3.300701e+02 +10 3261 -3.101000e+02 -3.947600e+02 +11 3261 2.459600e+02 1.371300e+02 +12 3261 -9.421100e+02 -5.095000e+02 +18 3261 -5.295600e+02 8.739990e+00 +2 3262 -4.480800e+02 9.137000e+01 +7 3262 1.344301e+02 3.346200e+02 +9 3262 -4.484600e+02 2.028401e+02 +10 3262 -3.368700e+02 -3.916500e+02 +11 3262 2.082300e+02 1.410500e+02 +20 3262 -4.716899e+02 -1.881100e+02 +2 3263 -2.242600e+02 1.664500e+02 +7 3263 2.969600e+02 3.829000e+02 +9 3263 -2.697800e+02 2.731400e+02 +10 3263 -2.013600e+02 -3.487200e+02 +11 3263 3.765200e+02 2.089400e+02 +12 3263 -8.169700e+02 -4.535400e+02 +13 3263 -1.588930e+03 6.843600e+02 +18 3263 -4.398300e+02 5.348999e+01 +20 3263 -3.725000e+02 -1.522900e+02 +2 3264 -3.797300e+02 2.002600e+02 +7 3264 1.781300e+02 3.999900e+02 +10 3264 -2.981400e+02 -3.324399e+02 +11 3264 2.574500e+02 2.219800e+02 +20 3264 -4.422800e+02 -1.434000e+02 +2 3265 -3.797300e+02 2.002600e+02 +4 3265 8.264299e+02 3.667700e+02 +7 3265 1.781700e+02 3.998800e+02 +9 3265 -3.967300e+02 2.876799e+02 +10 3265 -2.981400e+02 -3.324399e+02 +11 3265 2.574500e+02 2.219800e+02 +20 3265 -4.422800e+02 -1.434000e+02 +2 3266 -4.597600e+02 2.037800e+02 +4 3266 7.826799e+02 3.669900e+02 +5 3266 3.019100e+02 7.424399e+02 +7 3266 1.267800e+02 4.009399e+02 +9 3266 -4.574500e+02 2.882800e+02 +10 3266 -3.430400e+02 -3.307100e+02 +11 3266 1.983900e+02 2.226000e+02 +16 3266 3.330100e+02 3.909600e+02 +18 3266 -5.614600e+02 6.562000e+01 +20 3266 -4.764100e+02 -1.422700e+02 +2 3267 -4.597600e+02 2.037800e+02 +4 3267 7.826799e+02 3.669900e+02 +5 3267 3.019100e+02 7.424399e+02 +9 3267 -4.574500e+02 2.882800e+02 +10 3267 -3.430400e+02 -3.307100e+02 +11 3267 1.983900e+02 2.226000e+02 +20 3267 -4.764100e+02 -1.422700e+02 +2 3268 -2.390700e+02 2.119400e+02 +4 3268 9.384299e+02 3.760701e+02 +5 3268 5.047100e+02 7.804200e+02 +7 3268 2.853800e+02 4.081300e+02 +9 3268 -2.817700e+02 3.051200e+02 +10 3268 -2.112100e+02 -3.254700e+02 +11 3268 3.645900e+02 2.390100e+02 +12 3268 -8.281000e+02 -4.294399e+02 +13 3268 -1.629540e+03 7.952200e+02 +18 3268 -4.468199e+02 7.296997e+01 +20 3268 -3.787300e+02 -1.355400e+02 +2 3269 -2.932400e+02 2.543900e+02 +7 3269 2.382000e+02 4.337100e+02 +10 3269 -2.472100e+02 -3.023300e+02 +11 3269 3.218900e+02 2.661100e+02 +12 3269 -8.699300e+02 -4.055699e+02 +18 3269 -4.772600e+02 9.117993e+01 +20 3269 -4.044500e+02 -1.195500e+02 +2 3270 -5.604500e+02 2.718900e+02 +7 3270 6.950000e+01 4.401899e+02 +10 3270 -3.966300e+02 -2.943700e+02 +16 3270 2.892400e+02 4.193600e+02 +2 3271 -5.723200e+02 2.891900e+02 +7 3271 6.198999e+01 4.505300e+02 +16 3271 2.820400e+02 4.266899e+02 +2 3272 -2.875000e+02 3.418300e+02 +7 3272 2.418400e+02 4.874700e+02 +9 3272 -3.242900e+02 4.000400e+02 +10 3272 -2.440200e+02 -2.551100e+02 +11 3272 3.270300e+02 3.330400e+02 +12 3272 -8.643800e+02 -3.538400e+02 +18 3272 -4.734399e+02 1.336000e+02 +2 3273 -6.711400e+02 3.428200e+02 +7 3273 5.550049e+00 4.813800e+02 +9 3273 -6.197900e+02 3.923700e+02 +14 3273 4.588700e+02 3.098000e+02 +16 3273 2.402700e+02 4.488700e+02 +2 3274 -6.711400e+02 3.428200e+02 +7 3274 5.550049e+00 4.813800e+02 +2 3275 -4.037600e+02 3.551100e+02 +7 3275 1.618000e+02 4.921100e+02 +11 3275 2.390900e+02 3.348800e+02 +2 3276 -6.006500e+02 3.644900e+02 +7 3276 4.469995e+01 4.948900e+02 +9 3276 -5.675300e+02 4.099399e+02 +10 3276 -4.186801e+02 -2.448199e+02 +11 3276 9.630005e+01 3.375500e+02 +12 3276 -1.062980e+03 -3.410300e+02 +16 3276 2.685000e+02 4.607500e+02 +18 3276 -6.261900e+02 1.423000e+02 +2 3277 -6.006500e+02 3.644900e+02 +7 3277 4.469995e+01 4.948900e+02 +2 3278 -6.302000e+02 3.992600e+02 +5 3278 1.879100e+02 8.417500e+02 +7 3278 2.921997e+01 5.148500e+02 +9 3278 -5.908600e+02 4.350500e+02 +10 3278 -4.334200e+02 -2.267200e+02 +11 3278 7.456006e+01 3.617200e+02 +12 3278 -1.078900e+03 -3.206600e+02 +16 3278 2.570800e+02 4.751799e+02 +18 3278 -6.399500e+02 1.582800e+02 +20 3278 -5.449200e+02 -6.256006e+01 +2 3279 -6.302000e+02 3.992600e+02 +7 3279 2.921997e+01 5.148500e+02 +9 3279 -5.908600e+02 4.350500e+02 +10 3279 -4.334200e+02 -2.267200e+02 +11 3279 7.456006e+01 3.617200e+02 +12 3279 -1.078900e+03 -3.206600e+02 +20 3279 -5.449200e+02 -6.256006e+01 +2 3280 -6.863600e+02 3.990700e+02 +7 3280 -1.119995e+00 5.140400e+02 +9 3280 -6.321700e+02 4.354800e+02 +10 3280 -4.625900e+02 -2.272900e+02 +11 3280 3.471997e+01 3.623101e+02 +12 3280 -1.112190e+03 -3.192800e+02 +14 3280 4.550500e+02 3.296400e+02 +16 3280 2.348500e+02 4.737000e+02 +18 3280 -6.658900e+02 1.596300e+02 +20 3280 -5.676300e+02 -6.107996e+01 +2 3281 -6.863600e+02 3.990700e+02 +7 3281 -1.119995e+00 5.140400e+02 +10 3281 -4.625900e+02 -2.272900e+02 +12 3281 -1.112190e+03 -3.192800e+02 +14 3281 4.550500e+02 3.296400e+02 +16 3281 2.348500e+02 4.737000e+02 +18 3281 -6.658900e+02 1.596300e+02 +20 3281 -5.676300e+02 -6.107996e+01 +2 3282 -3.281300e+02 4.210400e+02 +7 3282 2.171100e+02 5.317800e+02 +9 3282 -3.574200e+02 4.592200e+02 +10 3282 -2.650200e+02 -2.147300e+02 +11 3282 2.992100e+02 3.858300e+02 +12 3282 -8.878300e+02 -3.079900e+02 +20 3282 -4.155000e+02 -5.293005e+01 +2 3283 6.598400e+02 4.310000e+02 +3 3283 7.373700e+02 6.103500e+02 +2 3284 6.133300e+02 -3.590900e+02 +7 3284 1.276899e+02 7.484998e+01 +16 3284 1.029500e+02 1.314000e+02 +2 3285 -4.212700e+02 -1.702900e+02 +7 3285 1.519800e+02 1.812200e+02 +9 3285 -4.253600e+02 8.189941e+00 +2 3286 -3.816000e+02 -1.370400e+02 +7 3286 1.752700e+02 1.988000e+02 +9 3286 -3.956600e+02 3.255005e+01 +11 3286 2.575000e+02 -2.251001e+01 +2 3287 -2.414000e+02 -4.929999e+01 +7 3287 2.755500e+02 2.514600e+02 +9 3287 -2.829200e+02 1.047000e+02 +11 3287 3.622300e+02 4.625000e+01 +18 3287 -4.509100e+02 -5.183997e+01 +20 3287 -3.832600e+02 -2.429301e+02 +2 3288 -2.704600e+02 -4.665997e+01 +7 3288 2.525500e+02 2.526100e+02 +9 3288 -3.074900e+02 1.041801e+02 +10 3288 -2.335400e+02 -4.660699e+02 +11 3288 3.404800e+02 4.576001e+01 +18 3288 -4.671899e+02 -5.171997e+01 +2 3289 -4.541300e+02 -4.371002e+01 +7 3289 1.291200e+02 2.541400e+02 +9 3289 -4.525601e+02 1.011899e+02 +18 3289 -5.593700e+02 -5.157996e+01 +20 3289 -4.753600e+02 -2.434600e+02 +2 3290 -5.309100e+02 -4.246002e+01 +7 3290 8.356006e+01 2.546300e+02 +10 3290 -3.835699e+02 -4.644800e+02 +11 3290 1.490601e+02 4.295001e+01 +16 3290 3.008700e+02 2.782500e+02 +18 3290 -5.964200e+02 -5.107996e+01 +20 3290 -5.081200e+02 -2.430601e+02 +2 3291 4.369000e+02 -3.501001e+01 +3 3291 4.018199e+02 -9.688000e+01 +17 3291 -1.526850e+03 2.815000e+02 +2 3292 -4.371800e+02 -2.940997e+01 +7 3292 1.407900e+02 2.626799e+02 +9 3292 -4.391899e+02 1.122900e+02 +10 3292 -3.306700e+02 -4.571400e+02 +11 3292 2.168000e+02 5.352002e+01 +20 3292 -4.680900e+02 -2.378500e+02 +2 3293 6.158500e+02 -2.759998e+01 +3 3293 7.632500e+02 1.482001e+01 +6 3293 7.034500e+02 -1.048200e+02 +12 3293 -2.842000e+02 -5.721400e+02 +17 3293 -1.178580e+03 2.909800e+02 +2 3294 4.174000e+02 -1.071997e+01 +3 3294 3.710100e+02 -7.477002e+01 +11 3294 9.229301e+02 1.124200e+02 +17 3294 -1.564050e+03 3.223600e+02 +2 3295 -4.525900e+02 2.323999e+01 +7 3295 1.320400e+02 2.944099e+02 +10 3295 -3.389100e+02 -4.286000e+02 +11 3295 2.052500e+02 9.228998e+01 +20 3295 -4.740200e+02 -2.154200e+02 +2 3296 -4.525900e+02 2.323999e+01 +7 3296 1.320400e+02 2.944099e+02 +10 3296 -3.389100e+02 -4.286000e+02 +11 3296 2.052500e+02 9.228998e+01 +18 3296 -5.573500e+02 -1.960999e+01 +20 3296 -4.740200e+02 -2.154200e+02 +2 3297 -3.602100e+02 2.690997e+01 +7 3297 1.891100e+02 2.958500e+02 +11 3297 2.722600e+02 9.571002e+01 +18 3297 -5.134000e+02 -1.823999e+01 +2 3298 -4.512400e+02 5.323999e+01 +7 3298 1.327000e+02 3.116500e+02 +10 3298 -3.376500e+02 -4.125400e+02 +11 3298 2.057600e+02 1.141200e+02 +12 3298 -9.770300e+02 -5.296400e+02 +18 3298 -5.571300e+02 -5.280029e+00 +20 3298 -4.735100e+02 -2.029800e+02 +2 3299 -4.380500e+02 6.403003e+01 +4 3299 7.924700e+02 3.025801e+02 +7 3299 1.398900e+02 3.179399e+02 +9 3299 -4.410601e+02 1.825500e+02 +10 3299 -3.318000e+02 -4.066100e+02 +11 3299 2.148600e+02 1.211100e+02 +18 3299 -5.507300e+02 -1.000000e+00 +2 3300 7.265100e+02 8.065002e+01 +3 3300 9.861899e+02 2.370000e+02 +16 3300 9.558700e+02 3.540000e+02 +17 3300 -1.001930e+03 4.499000e+02 +2 3301 -5.776600e+02 9.807001e+01 +7 3301 5.858997e+01 3.375901e+02 +9 3301 -5.491000e+02 2.072100e+02 +11 3301 1.154600e+02 1.440500e+02 +16 3301 2.812100e+02 3.410200e+02 +2 3302 -4.501000e+02 1.162900e+02 +4 3302 7.875901e+02 3.256500e+02 +7 3302 1.333400e+02 3.497000e+02 +9 3302 -4.506300e+02 2.231100e+02 +10 3302 -3.373600e+02 -3.788800e+02 +11 3302 2.061700e+02 1.596500e+02 +12 3302 -9.759300e+02 -4.906899e+02 +16 3302 3.399200e+02 3.513000e+02 +18 3302 -5.553700e+02 2.347998e+01 +20 3302 -4.726000e+02 -1.778300e+02 +2 3303 -2.008600e+02 1.434600e+02 +7 3303 3.231700e+02 3.688401e+02 +10 3303 -1.834800e+02 -3.613900e+02 +11 3303 3.961700e+02 1.945800e+02 +12 3303 -7.944700e+02 -4.663600e+02 +13 3303 -1.508050e+03 6.226300e+02 +18 3303 -4.244399e+02 4.360999e+01 +2 3304 -4.511100e+02 1.595300e+02 +7 3304 1.330400e+02 3.719299e+02 +9 3304 -4.520601e+02 2.544399e+02 +10 3304 -3.380000e+02 -3.570100e+02 +11 3304 2.056899e+02 1.856500e+02 +2 3305 -3.743600e+02 1.687100e+02 +7 3305 1.815000e+02 3.805100e+02 +9 3305 -3.924301e+02 2.642100e+02 +10 3305 -2.953900e+02 -3.502300e+02 +11 3305 2.616200e+02 1.993300e+02 +18 3305 -5.182500e+02 4.922998e+01 +2 3306 -5.411200e+02 1.819100e+02 +7 3306 8.119995e+01 3.887400e+02 +9 3306 -5.195900e+02 2.717100e+02 +11 3306 1.421801e+02 2.062400e+02 +2 3307 5.064200e+02 1.949500e+02 +3 3307 5.169301e+02 2.718800e+02 +17 3307 -1.396630e+03 6.380300e+02 +2 3308 -1.865900e+02 2.118500e+02 +7 3308 3.352400e+02 4.100200e+02 +9 3308 -2.348900e+02 3.132500e+02 +10 3308 -1.742500e+02 -3.241600e+02 +11 3308 4.071801e+02 2.483800e+02 +12 3308 -7.822300e+02 -4.240900e+02 +13 3308 -1.462780e+03 7.919399e+02 +20 3308 -3.525300e+02 -1.334301e+02 +2 3309 -4.089400e+02 2.247600e+02 +5 3309 3.358300e+02 7.633201e+02 +7 3309 1.604500e+02 4.135300e+02 +9 3309 -4.188101e+02 3.053500e+02 +11 3309 2.354399e+02 2.397800e+02 +18 3309 -5.347300e+02 7.505005e+01 +2 3310 -4.842300e+02 2.365900e+02 +7 3310 1.100900e+02 4.207700e+02 +9 3310 -4.800200e+02 3.138800e+02 +11 3310 1.791700e+02 2.459800e+02 +16 3310 3.198500e+02 4.059299e+02 +2 3311 -5.049200e+02 2.381300e+02 +7 3311 9.984998e+01 4.207100e+02 +9 3311 -4.934399e+02 3.140100e+02 +11 3311 1.662800e+02 2.459600e+02 +18 3311 -5.817700e+02 8.109998e+01 +2 3312 -5.442300e+02 2.707400e+02 +7 3312 7.967004e+01 4.413201e+02 +20 3312 -5.110400e+02 -1.144301e+02 +2 3313 -2.692500e+02 3.086000e+02 +4 3313 9.065000e+02 4.212800e+02 +5 3313 4.533500e+02 8.342300e+02 +7 3313 2.578700e+02 4.664500e+02 +9 3313 -3.091500e+02 3.773000e+02 +10 3313 -2.321100e+02 -2.725400e+02 +11 3313 3.403400e+02 3.089200e+02 +12 3313 -8.502500e+02 -3.722600e+02 +18 3313 -4.640100e+02 1.179600e+02 +2 3314 -6.998400e+02 3.577400e+02 +7 3314 -9.180054e+00 4.895601e+02 +16 3314 2.292300e+02 4.548700e+02 +2 3315 -6.750600e+02 3.754400e+02 +7 3315 4.339966e+00 4.995000e+02 +9 3315 -6.237900e+02 4.167700e+02 +11 3315 4.305005e+01 3.434100e+02 +14 3315 4.584400e+02 3.211900e+02 +18 3315 -6.610500e+02 1.466899e+02 +2 3316 -3.133200e+02 3.797600e+02 +7 3316 2.265200e+02 5.072000e+02 +9 3316 -3.451200e+02 4.261100e+02 +10 3316 -2.571000e+02 -2.358600e+02 +12 3316 -8.792100e+02 -3.319900e+02 +2 3317 -3.380500e+02 3.943400e+02 +7 3317 2.078500e+02 5.176400e+02 +9 3317 -3.654500e+02 4.379700e+02 +10 3317 -2.727300e+02 -2.271200e+02 +18 3317 -4.976100e+02 1.570801e+02 +20 3317 -4.218700e+02 -6.381995e+01 +2 3318 -3.141500e+02 3.986900e+02 +7 3318 2.262400e+02 5.209700e+02 +9 3318 -3.454000e+02 4.438800e+02 +10 3318 -2.576100e+02 -2.241000e+02 +11 3318 3.073400e+02 3.743500e+02 +12 3318 -8.790300e+02 -3.190000e+02 +2 3319 -5.339000e+02 4.007000e+02 +7 3319 8.441003e+01 5.168201e+02 +9 3319 -5.170800e+02 4.368401e+02 +10 3319 -3.822100e+02 -2.260800e+02 +11 3319 1.437700e+02 3.655800e+02 +16 3319 2.992700e+02 4.780200e+02 +2 3320 -7.441300e+02 4.033600e+02 +7 3320 -3.138000e+01 5.155500e+02 +9 3320 -6.749300e+02 4.387600e+02 +10 3320 -4.930601e+02 -2.242300e+02 +11 3320 -6.419983e+00 3.650900e+02 +12 3320 -1.145250e+03 -3.160900e+02 +14 3320 4.353000e+02 3.298900e+02 +18 3320 -6.925600e+02 1.611500e+02 +20 3320 -5.902300e+02 -5.976001e+01 +2 3321 -6.760300e+02 4.109000e+02 +7 3321 4.319946e+00 5.209600e+02 +9 3321 -6.253700e+02 4.436699e+02 +10 3321 -4.575601e+02 -2.203300e+02 +11 3321 4.028003e+01 3.706400e+02 +14 3321 4.590100e+02 3.337200e+02 +18 3321 -6.617800e+02 1.643700e+02 +2 3322 -3.436700e+02 4.137500e+02 +7 3322 2.031500e+02 5.299199e+02 +9 3322 -3.705100e+02 4.531599e+02 +10 3322 -2.761600e+02 -2.160300e+02 +11 3322 2.841801e+02 3.817300e+02 +12 3322 -8.997300e+02 -3.087700e+02 +18 3322 -5.017300e+02 1.664099e+02 +20 3322 -4.255601e+02 -5.495996e+01 +2 3323 5.784000e+02 4.148500e+02 +3 3323 6.147100e+02 5.908500e+02 +17 3323 -1.276990e+03 9.759700e+02 +2 3324 -7.317500e+02 4.170700e+02 +7 3324 -2.497998e+01 5.240500e+02 +9 3324 -6.667400e+02 4.487400e+02 +10 3324 -4.856200e+02 -2.172000e+02 +11 3324 1.910034e+00 3.744200e+02 +12 3324 -1.137560e+03 -3.079700e+02 +14 3324 4.393900e+02 3.350800e+02 +18 3324 -6.869800e+02 1.679099e+02 +20 3324 -5.857300e+02 -5.447998e+01 +2 3325 -7.318700e+02 4.362500e+02 +7 3325 -2.512000e+01 5.357100e+02 +9 3325 -6.672500e+02 4.638301e+02 +10 3325 -4.857600e+02 -2.072600e+02 +11 3325 1.420044e+00 3.883400e+02 +16 3325 2.170601e+02 4.886799e+02 +2 3326 -4.330900e+02 -1.788700e+02 +7 3326 1.420500e+02 1.742400e+02 +9 3326 -4.348500e+02 -7.600098e-01 +11 3326 2.205100e+02 -5.504999e+01 +18 3326 -5.497800e+02 -1.160900e+02 +20 3326 -4.676600e+02 -2.991000e+02 +2 3327 -4.333800e+02 -1.259400e+02 +7 3327 1.419301e+02 2.045901e+02 +9 3327 -4.362300e+02 3.926001e+01 +10 3327 -3.293900e+02 -5.098101e+02 +11 3327 2.198300e+02 -1.623999e+01 +2 3328 7.016100e+02 -1.175700e+02 +3 3328 9.433601e+02 -1.207400e+02 +2 3329 6.387800e+02 -9.954999e+01 +3 3329 8.022400e+02 -1.082500e+02 +2 3330 -4.080400e+02 -8.757001e+01 +7 3330 1.596200e+02 2.287900e+02 +11 3330 2.389700e+02 1.128998e+01 +18 3330 -5.368600e+02 -7.357996e+01 +2 3331 -4.484500e+02 -8.716998e+01 +4 3331 7.856399e+02 2.331799e+02 +7 3331 1.336200e+02 2.277800e+02 +9 3331 -4.472700e+02 6.863000e+01 +10 3331 -3.367100e+02 -4.895601e+02 +11 3331 2.092600e+02 1.020001e+01 +18 3331 -5.561000e+02 -7.413000e+01 +20 3331 -4.730900e+02 -2.618600e+02 +2 3332 -3.977400e+02 -7.303003e+01 +7 3332 1.630200e+02 2.375601e+02 +9 3332 -4.119200e+02 8.181995e+01 +10 3332 -3.092800e+02 -4.811500e+02 +11 3332 2.451000e+02 2.256000e+01 +12 3332 -9.477700e+02 -6.052900e+02 +2 3333 -2.938800e+02 -3.356000e+01 +7 3333 2.386200e+02 2.594600e+02 +9 3333 -3.240500e+02 1.120000e+02 +10 3333 -2.459900e+02 -4.595300e+02 +11 3333 3.251000e+02 5.314001e+01 +12 3333 -8.747200e+02 -5.799000e+02 +18 3333 -4.791300e+02 -4.646997e+01 +20 3333 -4.061801e+02 -2.384301e+02 +2 3334 -4.618000e+02 -3.077002e+01 +4 3334 7.794700e+02 2.588600e+02 +5 3334 3.197400e+02 5.982000e+02 +7 3334 1.252400e+02 2.617600e+02 +10 3334 -3.450100e+02 -4.578800e+02 +11 3334 1.986300e+02 5.192999e+01 +12 3334 -9.874400e+02 -5.796200e+02 +18 3334 -5.623700e+02 -4.596997e+01 +20 3334 -4.784600e+02 -2.384900e+02 +2 3335 -4.515800e+02 -2.253998e+01 +4 3335 7.854600e+02 2.626200e+02 +5 3335 3.272200e+02 6.041100e+02 +7 3335 1.321200e+02 2.669099e+02 +9 3335 -4.502600e+02 1.164301e+02 +10 3335 -3.386700e+02 -4.534200e+02 +11 3335 2.060500e+02 5.809003e+01 +12 3335 -9.795900e+02 -5.745200e+02 +18 3335 -5.572700e+02 -4.206995e+01 +2 3336 -3.873500e+02 -2.231000e+01 +4 3336 8.202000e+02 2.634099e+02 +5 3336 3.718800e+02 6.118500e+02 +7 3336 1.728000e+02 2.679399e+02 +9 3336 -4.011500e+02 1.178500e+02 +10 3336 -3.022800e+02 -4.528500e+02 +11 3336 2.529600e+02 5.808002e+01 +12 3336 -9.382700e+02 -5.741700e+02 +18 3336 -5.261200e+02 -4.118005e+01 +20 3336 -4.470900e+02 -2.347100e+02 +2 3337 -3.983000e+02 -1.954999e+01 +7 3337 1.654600e+02 2.686799e+02 +10 3337 -3.085900e+02 -4.515100e+02 +12 3337 -9.456000e+02 -5.725000e+02 +18 3337 -5.315100e+02 -4.030005e+01 +2 3338 -3.983000e+02 -1.954999e+01 +7 3338 1.654600e+02 2.686799e+02 +9 3338 -4.087000e+02 1.201600e+02 +10 3338 -3.085900e+02 -4.515100e+02 +11 3338 2.451100e+02 6.152002e+01 +12 3338 -9.456000e+02 -5.725000e+02 +18 3338 -5.315100e+02 -4.030005e+01 +20 3338 -4.513500e+02 -2.336801e+02 +2 3339 -3.981500e+02 -4.150024e+00 +7 3339 1.657100e+02 2.777200e+02 +9 3339 -4.093400e+02 1.328000e+02 +11 3339 2.452700e+02 7.244000e+01 +2 3340 -2.907400e+02 6.929993e+00 +7 3340 2.384399e+02 2.850500e+02 +10 3340 -2.462300e+02 -4.364399e+02 +11 3340 3.250000e+02 8.453998e+01 +2 3341 -3.740400e+02 3.927002e+01 +7 3341 1.811899e+02 3.029099e+02 +9 3341 -3.913700e+02 1.641100e+02 +10 3341 -2.951801e+02 -4.198000e+02 +11 3341 2.624100e+02 1.051400e+02 +12 3341 -9.290000e+02 -5.355400e+02 +2 3342 -4.613500e+02 6.315002e+01 +7 3342 1.268199e+02 3.179500e+02 +9 3342 -4.577600e+02 1.822900e+02 +2 3343 -5.268400e+02 7.440997e+01 +7 3343 8.677002e+01 3.238700e+02 +9 3343 -5.079200e+02 1.896699e+02 +12 3343 -1.025480e+03 -5.154600e+02 +16 3343 3.034900e+02 3.309600e+02 +18 3343 -5.937600e+02 3.569946e+00 +2 3344 -5.268400e+02 7.440997e+01 +7 3344 8.677002e+01 3.238700e+02 +16 3344 3.034900e+02 3.309600e+02 +2 3345 -5.468100e+02 8.573999e+01 +7 3345 7.572998e+01 3.303800e+02 +9 3345 -5.243500e+02 1.981699e+02 +10 3345 -3.910000e+02 -3.949500e+02 +11 3345 1.364700e+02 1.353600e+02 +12 3345 -1.037020e+03 -5.090601e+02 +20 3345 -5.130900e+02 -1.906899e+02 +2 3346 3.712500e+02 8.714001e+01 +3 3346 2.977700e+02 2.406000e+01 +2 3347 -2.929200e+02 1.034700e+02 +7 3347 2.370300e+02 3.429099e+02 +10 3347 -2.472800e+02 -3.840800e+02 +11 3347 3.226500e+02 1.549000e+02 +12 3347 -8.732300e+02 -4.957200e+02 +2 3348 6.243800e+02 1.056700e+02 +3 3348 7.702300e+02 2.381500e+02 +12 3348 -2.812100e+02 -4.920300e+02 +17 3348 -1.169190e+03 4.921300e+02 +2 3349 -2.602100e+02 1.093500e+02 +3 3349 -8.294800e+02 3.313600e+02 +7 3349 2.661300e+02 3.492000e+02 +10 3349 -2.250500e+02 -3.807100e+02 +12 3349 -8.460000e+02 -4.919100e+02 +20 3349 -3.893300e+02 -1.777600e+02 +2 3350 3.948101e+02 1.108300e+02 +3 3350 3.295400e+02 6.052002e+01 +11 3350 9.136300e+02 2.178400e+02 +17 3350 -1.621710e+03 5.125701e+02 +2 3351 -3.879400e+02 1.134400e+02 +7 3351 1.728600e+02 3.463600e+02 +9 3351 -4.022000e+02 2.200500e+02 +10 3351 -3.027400e+02 -3.798500e+02 +11 3351 2.522200e+02 1.578600e+02 +12 3351 -9.360700e+02 -4.924100e+02 +18 3351 -5.253000e+02 2.215002e+01 +20 3351 -4.461100e+02 -1.795000e+02 +2 3352 -4.094800e+02 1.137500e+02 +7 3352 1.366400e+02 3.458500e+02 +9 3352 -4.186100e+02 2.214199e+02 +11 3352 2.359700e+02 1.579600e+02 +20 3352 -4.551100e+02 -1.789200e+02 +2 3353 6.870500e+02 1.466100e+02 +3 3353 9.067200e+02 3.453600e+02 +2 3354 -2.499000e+02 1.928100e+02 +7 3354 2.760900e+02 3.981500e+02 +10 3354 -2.182100e+02 -3.352900e+02 +11 3354 3.568700e+02 2.236100e+02 +12 3354 -8.357900e+02 -4.395900e+02 +18 3354 -4.519100e+02 6.232007e+01 +2 3355 -2.385400e+02 1.974000e+02 +3 3355 -7.695900e+02 4.753900e+02 +9 3355 -2.810601e+02 2.952200e+02 +10 3355 -2.106600e+02 -3.318400e+02 +11 3355 3.652400e+02 2.294400e+02 +13 3355 -1.628180e+03 7.624500e+02 +18 3355 -4.468000e+02 6.609998e+01 +2 3356 -4.710500e+02 2.385600e+02 +4 3356 7.772100e+02 3.826799e+02 +5 3356 2.904399e+02 7.617300e+02 +7 3356 1.195601e+02 4.213201e+02 +9 3356 -4.672500e+02 3.140200e+02 +11 3356 1.895601e+02 2.474600e+02 +16 3356 3.276000e+02 4.063300e+02 +2 3357 -5.747400e+02 2.708000e+02 +7 3357 6.027002e+01 4.396000e+02 +9 3357 -5.463100e+02 3.423301e+02 +16 3357 2.815500e+02 4.192800e+02 +2 3358 -5.116800e+02 3.147600e+02 +7 3358 9.713000e+01 4.665000e+02 +11 3358 1.605300e+02 3.022300e+02 +2 3359 -4.908900e+02 3.194500e+02 +7 3359 1.085900e+02 4.698201e+02 +9 3359 -4.828500e+02 3.750200e+02 +11 3359 1.761899e+02 3.059900e+02 +18 3359 -5.745900e+02 1.201599e+02 +2 3360 -4.472200e+02 3.288200e+02 +5 3360 3.003101e+02 8.213700e+02 +7 3360 1.349600e+02 4.758700e+02 +11 3360 2.077000e+02 3.144200e+02 +2 3361 6.895500e+02 3.700300e+02 +7 3361 9.632700e+02 5.262800e+02 +17 3361 -1.107380e+03 9.002400e+02 +2 3362 6.895500e+02 3.700300e+02 +7 3362 9.632700e+02 5.262800e+02 +17 3362 -1.107380e+03 9.002400e+02 +20 3362 4.008997e+01 -5.372998e+01 +2 3363 -7.520500e+02 3.735700e+02 +7 3363 -3.653003e+01 4.979000e+02 +9 3363 -6.818500e+02 4.153000e+02 +11 3363 -1.187000e+01 3.432300e+02 +16 3363 2.091300e+02 4.604200e+02 +2 3364 -6.041600e+02 3.791400e+02 +7 3364 4.207996e+01 5.023700e+02 +9 3364 -5.699100e+02 4.190901e+02 +10 3364 -4.202700e+02 -2.372700e+02 +11 3364 9.385999e+01 3.470400e+02 +18 3364 -6.282000e+02 1.474700e+02 +20 3364 -5.341800e+02 -7.110999e+01 +2 3365 -5.850900e+02 4.051700e+02 +7 3365 5.430005e+01 5.181599e+02 +9 3365 -5.558300e+02 4.434199e+02 +10 3365 -4.096300e+02 -2.240601e+02 +16 3365 2.760300e+02 4.796400e+02 +2 3366 -5.258200e+02 4.102600e+02 +7 3366 8.704004e+01 5.237300e+02 +9 3366 -5.119100e+02 4.448600e+02 +10 3366 -3.779900e+02 -2.201400e+02 +11 3366 1.490500e+02 3.732200e+02 +16 3366 3.025699e+02 4.831300e+02 +2 3367 -2.597900e+02 4.152500e+02 +4 3367 9.322600e+02 4.696500e+02 +9 3367 -3.010900e+02 4.614800e+02 +11 3367 3.481300e+02 3.905900e+02 +2 3368 -4.777500e+02 4.252900e+02 +7 3368 1.161000e+02 5.333600e+02 +9 3368 -4.752200e+02 4.569199e+02 +10 3368 -3.509700e+02 -2.093800e+02 +11 3368 1.841000e+02 3.848500e+02 +12 3368 -9.843000e+02 -3.016801e+02 +2 3369 -5.866000e+02 4.305800e+02 +7 3369 5.363000e+01 5.341599e+02 +9 3369 -5.578200e+02 4.584700e+02 +10 3369 -4.104000e+02 -2.098700e+02 +11 3369 1.060900e+02 3.855100e+02 +2 3370 -5.858800e+02 4.427300e+02 +7 3370 5.412000e+01 5.420300e+02 +9 3370 -5.571600e+02 4.689500e+02 +10 3370 -4.098400e+02 -2.024600e+02 +11 3370 1.063600e+02 3.940900e+02 +2 3371 -3.976000e+02 4.445400e+02 +7 3371 1.677200e+02 5.463500e+02 +9 3371 -4.130800e+02 4.738201e+02 +10 3371 -3.069800e+02 -2.007600e+02 +11 3371 2.433900e+02 4.011300e+02 +12 3371 -9.345900e+02 -2.939200e+02 +18 3371 -5.276000e+02 1.798101e+02 +2 3372 -7.203700e+02 4.466100e+02 +7 3372 -1.983997e+01 5.429099e+02 +9 3372 -6.589700e+02 4.729099e+02 +10 3372 -4.792500e+02 -2.017100e+02 +11 3372 8.989990e+00 3.970800e+02 +12 3372 -1.130870e+03 -2.903800e+02 +18 3372 -6.820900e+02 1.824900e+02 +2 3373 -4.276500e+02 4.585100e+02 +4 3373 8.012300e+02 4.868401e+02 +5 3373 3.024600e+02 9.052100e+02 +7 3373 1.473900e+02 5.543401e+02 +10 3373 -3.237200e+02 -1.942700e+02 +12 3373 -9.543200e+02 -2.863700e+02 +2 3374 5.219600e+02 -3.054300e+02 +7 3374 5.529004e+01 1.046200e+02 +2 3375 4.582300e+02 -2.404300e+02 +7 3375 2.046997e+01 1.387500e+02 +2 3376 -6.390200e+02 -2.066600e+02 +7 3376 1.036200e+02 1.591400e+02 +2 3377 -5.105100e+02 -2.049000e+02 +7 3377 9.605005e+01 1.587900e+02 +10 3377 -3.725400e+02 -5.528800e+02 +20 3377 -5.000400e+02 -3.098101e+02 +2 3378 -2.207300e+02 -2.000500e+02 +3 3378 -7.341600e+02 -2.634200e+02 +6 3378 -3.916200e+02 -2.580900e+02 +9 3378 -2.635500e+02 -9.640015e+00 +10 3378 -1.995500e+02 -5.496500e+02 +11 3378 3.805500e+02 -6.444000e+01 +13 3378 -1.596290e+03 -2.281899e+02 +18 3378 -4.402000e+02 -1.236300e+02 +20 3378 -3.729900e+02 -3.049301e+02 +2 3379 -4.041400e+02 -1.752800e+02 +7 3379 1.615699e+02 1.754600e+02 +10 3379 -3.119900e+02 -5.364800e+02 +11 3379 2.411500e+02 -5.113000e+01 +12 3379 -9.521700e+02 -6.665400e+02 +18 3379 -5.353700e+02 -1.137100e+02 +2 3380 -3.925500e+02 -1.697600e+02 +7 3380 1.676600e+02 1.790601e+02 +9 3380 -4.041300e+02 3.089966e+00 +11 3380 2.497700e+02 -4.748999e+01 +18 3380 -5.300300e+02 -1.115000e+02 +20 3380 -4.506500e+02 -2.952600e+02 +2 3381 7.612400e+02 -1.541900e+02 +3 3381 1.066450e+03 -1.788900e+02 +7 3381 9.064700e+02 1.841400e+02 +2 3382 6.426400e+02 -1.345000e+02 +3 3382 8.061500e+02 -1.676400e+02 +2 3383 3.529399e+02 -1.174100e+02 +3 3383 2.720400e+02 -2.480500e+02 +2 3384 -2.871800e+02 -8.084998e+01 +7 3384 2.408600e+02 2.331500e+02 +9 3384 -3.208800e+02 7.782996e+01 +10 3384 -2.440699e+02 -4.844900e+02 +11 3384 3.278600e+02 2.066998e+01 +12 3384 -8.723200e+02 -6.068600e+02 +18 3384 -4.764200e+02 -6.880005e+01 +2 3385 -3.950300e+02 -6.452002e+01 +7 3385 1.653700e+02 2.417000e+02 +9 3385 -4.068000e+02 8.656006e+01 +18 3385 -5.307900e+02 -6.198999e+01 +2 3386 -3.953300e+02 -5.320001e+01 +7 3386 1.664200e+02 2.486200e+02 +9 3386 -4.067700e+02 9.503003e+01 +11 3386 2.479000e+02 3.690002e+01 +2 3387 5.739500e+02 -4.900000e+01 +3 3387 6.705100e+02 -4.028003e+01 +2 3388 -2.134600e+02 -4.663000e+01 +3 3388 -7.106600e+02 6.539978e+00 +7 3388 3.057800e+02 2.529099e+02 +9 3388 -2.579100e+02 1.099399e+02 +10 3388 -1.954500e+02 -4.658900e+02 +11 3388 3.854399e+02 5.090002e+01 +13 3388 -1.567000e+03 1.505000e+02 +18 3388 -4.346400e+02 -4.888000e+01 +20 3388 -3.682300e+02 -2.401000e+02 +2 3389 6.357100e+02 -4.021997e+01 +3 3389 7.940400e+02 -6.070007e+00 +17 3389 -1.151250e+03 2.686699e+02 +2 3390 -2.832000e+02 -2.897998e+01 +7 3390 2.438900e+02 2.626500e+02 +10 3390 -2.414301e+02 -4.570100e+02 +11 3390 3.300800e+02 5.756000e+01 +12 3390 -8.685100e+02 -5.772700e+02 +2 3391 -4.109900e+02 -2.476001e+01 +7 3391 1.576400e+02 2.663600e+02 +11 3391 2.360800e+02 5.695001e+01 +12 3391 -9.505200e+02 -5.769900e+02 +18 3391 -5.377400e+02 -4.231995e+01 +20 3391 -4.571700e+02 -2.356300e+02 +2 3392 6.676801e+02 -1.684998e+01 +3 3392 8.737300e+02 5.137000e+01 +17 3392 -1.095780e+03 3.032700e+02 +2 3393 -2.731500e+02 -1.140002e+01 +3 3393 -8.792700e+02 1.128600e+02 +7 3393 2.511801e+02 2.738500e+02 +9 3393 -3.106899e+02 1.308101e+02 +10 3393 -2.357100e+02 -4.465800e+02 +11 3393 3.378900e+02 7.141998e+01 +20 3393 -3.973300e+02 -2.289500e+02 +2 3394 6.783600e+02 -8.719971e+00 +3 3394 8.949000e+02 6.871997e+01 +17 3394 -1.077130e+03 3.153500e+02 +2 3395 6.197200e+02 -7.770020e+00 +3 3395 7.614700e+02 4.664001e+01 +2 3396 -2.822300e+02 -2.330017e+00 +7 3396 2.441801e+02 2.795300e+02 +10 3396 -2.410400e+02 -4.420300e+02 +11 3396 3.309700e+02 7.753003e+01 +12 3396 -8.678300e+02 -5.604900e+02 +20 3396 -4.013600e+02 -2.251801e+02 +2 3397 -5.021100e+02 2.840027e+00 +7 3397 1.010900e+02 2.814000e+02 +11 3397 1.694000e+02 7.571997e+01 +18 3397 -5.818000e+02 -3.032996e+01 +20 3397 -4.947900e+02 -2.247900e+02 +2 3398 4.533500e+02 5.549988e+00 +3 3398 4.293101e+02 -3.248999e+01 +17 3398 -1.491010e+03 3.451899e+02 +2 3399 -4.691500e+02 5.366998e+01 +7 3399 1.216500e+02 3.114600e+02 +9 3399 -4.635000e+02 1.746100e+02 +11 3399 1.930500e+02 1.132800e+02 +2 3400 -6.234998e+01 5.556000e+01 +3 3400 -2.686100e+02 -2.419983e+00 +2 3401 6.039100e+02 5.844000e+01 +3 3401 7.363300e+02 1.570800e+02 +17 3401 -1.202630e+03 4.214099e+02 +2 3402 3.907500e+02 6.303003e+01 +3 3402 3.279700e+02 4.699707e-01 +17 3402 -1.618920e+03 4.352100e+02 +2 3403 3.907500e+02 6.303003e+01 +3 3403 3.279700e+02 4.699707e-01 +11 3403 9.082300e+02 1.782700e+02 +17 3403 -1.618920e+03 4.352100e+02 +2 3404 4.448101e+02 6.962000e+01 +3 3404 4.021700e+02 3.059003e+01 +11 3404 9.483700e+02 1.779300e+02 +17 3404 -1.521600e+03 4.448600e+02 +2 3405 3.919600e+02 9.332001e+01 +3 3405 3.270699e+02 3.859998e+01 +11 3405 9.120601e+02 2.033800e+02 +17 3405 -1.622250e+03 4.862100e+02 +2 3406 -5.365900e+02 9.478003e+01 +7 3406 8.238000e+01 3.352300e+02 +9 3406 -5.162400e+02 2.048900e+02 +11 3406 1.445000e+02 1.419900e+02 +16 3406 2.982200e+02 3.400900e+02 +2 3407 -4.385200e+02 1.100700e+02 +4 3407 7.933601e+02 3.237600e+02 +7 3407 1.404800e+02 3.453700e+02 +9 3407 -4.415200e+02 2.172400e+02 +10 3407 -3.313300e+02 -3.813000e+02 +11 3407 2.149600e+02 1.547600e+02 +12 3407 -9.687700e+02 -4.945000e+02 +16 3407 3.449000e+02 3.488900e+02 +18 3407 -5.504700e+02 2.076001e+01 +20 3407 -4.677700e+02 -1.804600e+02 +2 3408 7.251300e+02 1.434100e+02 +6 3408 8.143800e+02 1.294100e+02 +2 3409 -2.287600e+02 1.609000e+02 +7 3409 2.949900e+02 3.787300e+02 +9 3409 -2.719399e+02 2.679600e+02 +10 3409 -2.038400e+02 -3.520300e+02 +11 3409 3.732200e+02 2.038900e+02 +12 3409 -8.204900e+02 -4.578101e+02 +13 3409 -1.598100e+03 6.702200e+02 +18 3409 -4.414600e+02 4.980005e+01 +20 3409 -3.737000e+02 -1.550000e+02 +2 3410 -3.873300e+02 1.759400e+02 +7 3410 1.731100e+02 3.848201e+02 +10 3410 -3.026600e+02 -3.454500e+02 +11 3410 2.530200e+02 2.054000e+02 +12 3410 -9.344800e+02 -4.551899e+02 +18 3410 -5.247400e+02 5.234998e+01 +2 3411 -3.264500e+02 1.808100e+02 +7 3411 2.132200e+02 3.889800e+02 +10 3411 -2.677100e+02 -3.425800e+02 +11 3411 2.970000e+02 2.097400e+02 +12 3411 -8.951700e+02 -4.506600e+02 +2 3412 -1.975800e+02 2.100200e+02 +7 3412 3.262600e+02 4.096899e+02 +9 3412 -2.439200e+02 3.115701e+02 +10 3412 -1.810699e+02 -3.247100e+02 +11 3412 3.991300e+02 2.452700e+02 +13 3412 -1.494700e+03 7.887800e+02 +2 3413 -1.975800e+02 2.100200e+02 +7 3413 3.262600e+02 4.096899e+02 +9 3413 -2.439200e+02 3.115701e+02 +10 3413 -1.810699e+02 -3.247100e+02 +11 3413 3.991300e+02 2.452700e+02 +13 3413 -1.494700e+03 7.887800e+02 +2 3414 -4.722300e+02 2.134900e+02 +4 3414 7.776001e+02 3.708201e+02 +5 3414 2.949500e+02 7.470200e+02 +7 3414 1.202400e+02 4.065200e+02 +9 3414 -4.681700e+02 2.960100e+02 +11 3414 1.899100e+02 2.293600e+02 +12 3414 -9.876700e+02 -4.320699e+02 +18 3414 -5.659000e+02 7.003003e+01 +2 3415 -4.722300e+02 2.134900e+02 +7 3415 1.202400e+02 4.065200e+02 +9 3415 -4.681700e+02 2.960100e+02 +11 3415 1.899100e+02 2.293600e+02 +12 3415 -9.876700e+02 -4.320699e+02 +18 3415 -5.659000e+02 7.003003e+01 +2 3416 -4.508300e+02 2.150200e+02 +7 3416 1.339000e+02 4.075000e+02 +11 3416 2.055800e+02 2.308000e+02 +12 3416 -9.725900e+02 -4.314000e+02 +18 3416 -5.554700e+02 7.068994e+01 +2 3417 -5.182200e+02 2.219200e+02 +7 3417 9.181006e+01 4.112900e+02 +11 3417 1.567600e+02 2.341800e+02 +2 3418 -3.678300e+02 2.973300e+02 +7 3418 1.854100e+02 4.579900e+02 +10 3418 -2.919301e+02 -2.789900e+02 +11 3418 2.652700e+02 2.943500e+02 +2 3419 6.896600e+02 3.421300e+02 +7 3419 9.628201e+02 5.071599e+02 +12 3419 -1.841200e+02 -3.307700e+02 +17 3419 -1.107170e+03 8.534800e+02 +20 3419 4.015002e+01 -6.692004e+01 +2 3420 6.894100e+02 3.527800e+02 +7 3420 9.628601e+02 5.148301e+02 +2 3421 -3.418400e+02 3.791700e+02 +7 3421 2.019700e+02 5.075000e+02 +9 3421 -3.702500e+02 4.255300e+02 +10 3421 -2.759700e+02 -2.351600e+02 +11 3421 2.832500e+02 3.542800e+02 +2 3422 -4.665100e+02 4.096500e+02 +4 3422 7.809900e+02 4.622100e+02 +7 3422 1.236899e+02 5.237400e+02 +10 3422 -3.463300e+02 -2.197700e+02 +11 3422 1.931700e+02 3.726899e+02 +12 3422 -9.794200e+02 -3.154800e+02 +18 3422 -5.618100e+02 1.626100e+02 +20 3422 -4.770601e+02 -5.833997e+01 +2 3423 -6.297700e+02 4.292700e+02 +7 3423 2.983997e+01 5.334000e+02 +9 3423 -5.900900e+02 4.589700e+02 +18 3423 -6.391800e+02 1.723500e+02 +20 3423 -5.442300e+02 -5.014001e+01 +2 3424 -6.297700e+02 4.292700e+02 +7 3424 2.983997e+01 5.334000e+02 +9 3424 -5.900900e+02 4.589700e+02 +10 3424 -4.327900e+02 -2.109200e+02 +11 3424 7.497998e+01 3.830701e+02 +18 3424 -6.391800e+02 1.723500e+02 +20 3424 -5.442300e+02 -5.014001e+01 +2 3425 -5.354500e+02 4.437000e+02 +7 3425 8.298999e+01 5.429500e+02 +9 3425 -5.184900e+02 4.701200e+02 +10 3425 -3.828600e+02 -2.024600e+02 +11 3425 1.430100e+02 3.955900e+02 +16 3425 2.984000e+02 4.982800e+02 +2 3426 -5.708700e+02 4.450400e+02 +7 3426 6.270996e+01 5.441699e+02 +9 3426 -5.479000e+02 4.732000e+02 +10 3426 -4.016801e+02 -2.013500e+02 +11 3426 1.175699e+02 3.967300e+02 +16 3426 2.839900e+02 4.981500e+02 +2 3427 -3.632000e+02 4.535400e+02 +7 3427 1.939399e+02 5.533101e+02 +9 3427 -3.844700e+02 4.846100e+02 +10 3427 -2.859301e+02 -1.948900e+02 +12 3427 -9.099200e+02 -2.855300e+02 +18 3427 -5.101400e+02 1.862800e+02 +20 3427 -4.322400e+02 -3.803003e+01 +2 3428 -4.473800e+02 4.586100e+02 +6 3428 -7.608200e+02 6.014500e+02 +8 3428 -9.967600e+02 7.481500e+02 +10 3428 -3.353199e+02 -1.931200e+02 +11 3428 2.068000e+02 4.101300e+02 +18 3428 -5.522400e+02 1.857100e+02 +2 3429 -4.351800e+02 4.667800e+02 +7 3429 1.428101e+02 5.587600e+02 +10 3429 -3.287200e+02 -1.894700e+02 +11 3429 2.151899e+02 4.157000e+02 +2 3430 5.100300e+02 -3.868500e+02 +7 3430 4.271997e+01 6.168994e+01 +2 3431 4.877700e+02 -3.256100e+02 +7 3431 3.214001e+01 9.455005e+01 +2 3432 -4.928000e+02 -2.276400e+02 +7 3432 1.058700e+02 1.456799e+02 +2 3433 -4.998600e+02 -2.210700e+02 +7 3433 1.020300e+02 1.496699e+02 +2 3434 -2.633500e+02 -2.151800e+02 +3 3434 -8.593300e+02 -2.818900e+02 +11 3434 3.464700e+02 -7.767999e+01 +2 3435 -5.082700e+02 -2.118000e+02 +7 3435 9.603003e+01 1.551599e+02 +2 3436 6.117300e+02 -2.057700e+02 +3 3436 7.530601e+02 -2.908500e+02 +6 3436 6.888101e+02 -3.257000e+02 +2 3437 -4.739600e+02 -2.048500e+02 +6 3437 -8.751100e+02 -2.225600e+02 +9 3437 -4.652600e+02 -2.093005e+01 +11 3437 1.912300e+02 -7.382001e+01 +20 3437 -4.860800e+02 -3.094301e+02 +2 3438 -4.966100e+02 -2.048200e+02 +7 3438 1.036200e+02 1.591400e+02 +9 3438 -4.830100e+02 -2.087000e+01 +18 3438 -5.804800e+02 -1.280601e+02 +20 3438 -4.943100e+02 -3.097300e+02 +2 3439 -3.526600e+02 -2.026600e+02 +7 3439 1.922700e+02 1.595300e+02 +12 3439 -9.212700e+02 -6.833900e+02 +18 3439 -5.111500e+02 -1.271000e+02 +20 3439 -4.334000e+02 -3.084200e+02 +2 3440 -2.571700e+02 -1.997100e+02 +3 3440 -8.358600e+02 -2.549000e+02 +10 3440 -2.240300e+02 -5.497100e+02 +11 3440 3.517400e+02 -6.583002e+01 +18 3440 -4.607800e+02 -1.243101e+02 +2 3441 7.458800e+02 -1.783200e+02 +3 3441 1.033680e+03 -2.239399e+02 +2 3442 7.458800e+02 -1.783200e+02 +3 3442 1.033680e+03 -2.239399e+02 +2 3443 -3.375200e+02 -1.654500e+02 +3 3443 -1.046090e+03 -1.735400e+02 +9 3443 -3.610800e+02 1.142004e+01 +11 3443 2.902700e+02 -4.385999e+01 +12 3443 -9.100400e+02 -6.603199e+02 +18 3443 -5.029500e+02 -1.092400e+02 +20 3443 -4.270000e+02 -2.932400e+02 +2 3444 -2.787800e+02 -1.593100e+02 +3 3444 -8.942600e+02 -1.700800e+02 +9 3444 -3.133101e+02 1.802002e+01 +10 3444 -2.395900e+02 -5.282900e+02 +11 3444 3.345400e+02 -3.734003e+01 +12 3444 -8.688800e+02 -6.558000e+02 +18 3444 -4.722100e+02 -1.054100e+02 +2 3445 6.300699e+02 -1.574700e+02 +3 3445 7.836600e+02 -2.082800e+02 +2 3446 7.460300e+02 -1.548200e+02 +3 3446 1.031590e+03 -1.827000e+02 +2 3447 -2.727200e+02 -8.846997e+01 +7 3447 2.513400e+02 2.275901e+02 +9 3447 -3.095200e+02 7.221997e+01 +10 3447 -2.353800e+02 -4.889600e+02 +12 3447 -8.625700e+02 -6.126801e+02 +2 3448 -3.343700e+02 -7.595001e+01 +7 3448 2.067300e+02 2.353301e+02 +9 3448 -3.581000e+02 8.058997e+01 +10 3448 -2.729000e+02 -4.830000e+02 +11 3448 2.921300e+02 2.203003e+01 +18 3448 -5.005500e+02 -6.722998e+01 +2 3449 -4.744600e+02 -7.613000e+01 +7 3449 1.171801e+02 2.350701e+02 +2 3450 4.508101e+02 -4.954999e+01 +3 3450 4.259399e+02 -1.097500e+02 +2 3451 4.565601e+02 -3.141998e+01 +3 3451 4.359100e+02 -8.575000e+01 +11 3451 9.471700e+02 9.165997e+01 +17 3451 -1.484700e+03 2.860901e+02 +2 3452 -4.278400e+02 -2.597998e+01 +7 3452 1.464100e+02 2.648401e+02 +12 3452 -9.654700e+02 -5.764100e+02 +18 3452 -5.458500e+02 -4.231995e+01 +2 3453 4.509600e+02 -2.538000e+01 +3 3453 4.254700e+02 -7.670001e+01 +11 3453 9.439600e+02 9.496997e+01 +17 3453 -1.495720e+03 2.972100e+02 +2 3454 4.509600e+02 -2.538000e+01 +3 3454 4.254700e+02 -7.670001e+01 +11 3454 9.439600e+02 9.496997e+01 +17 3454 -1.495720e+03 2.972100e+02 +2 3455 -2.317900e+02 -2.138000e+01 +3 3455 -7.550600e+02 6.306000e+01 +7 3455 2.905200e+02 2.685701e+02 +10 3455 -2.063000e+02 -4.522800e+02 +11 3455 3.710200e+02 6.775000e+01 +13 3455 -1.618120e+03 2.153401e+02 +2 3456 4.442600e+02 -3.849976e+00 +3 3456 4.158600e+02 -4.708002e+01 +17 3456 -1.506770e+03 3.315701e+02 +2 3457 -1.282000e+02 -9.799805e-01 +3 3457 -4.661700e+02 1.625000e+01 +4 3457 1.097130e+03 2.781000e+02 +8 3457 -1.414000e+02 6.365002e+01 +10 3457 -1.267700e+02 -4.388300e+02 +11 3457 4.588600e+02 9.760999e+01 +13 3457 -1.261270e+03 2.543700e+02 +20 3457 -3.198101e+02 -2.145900e+02 +2 3458 4.584600e+02 -4.600220e-01 +3 3458 4.395100e+02 -3.708002e+01 +11 3458 9.488600e+02 1.149900e+02 +17 3458 -1.481940e+03 3.356000e+02 +2 3459 -1.505200e+02 4.219971e+00 +7 3459 3.756600e+02 2.863201e+02 +9 3459 -1.976500e+02 1.590701e+02 +10 3459 -1.458101e+02 -4.359900e+02 +11 3459 4.395699e+02 9.758002e+01 +12 3459 -7.503500e+02 -5.452800e+02 +2 3460 -4.957200e+02 1.014001e+01 +7 3460 1.035200e+02 2.850701e+02 +9 3460 -4.838800e+02 1.406699e+02 +11 3460 1.740900e+02 8.088000e+01 +2 3461 -1.182300e+02 1.475000e+01 +3 3461 -4.422000e+02 3.570001e+01 +9 3461 -1.648000e+02 1.719500e+02 +11 3461 4.676300e+02 1.100700e+02 +13 3461 -1.224450e+03 2.908800e+02 +20 3461 -3.146100e+02 -2.073900e+02 +2 3462 4.459000e+02 2.002002e+01 +3 3462 4.187300e+02 -1.267999e+01 +17 3462 -1.504400e+03 3.690200e+02 +2 3463 -1.247000e+02 2.090002e+01 +3 3463 -4.555200e+02 4.866998e+01 +7 3463 4.106500e+02 2.965601e+02 +9 3463 -1.706200e+02 1.754299e+02 +10 3463 -1.231899e+02 -4.269800e+02 +11 3463 4.622900e+02 1.139500e+02 +12 3463 -7.208600e+02 -5.317600e+02 +13 3463 -1.244210e+03 3.074800e+02 +18 3463 -3.756700e+02 -8.390015e+00 +20 3463 -3.178000e+02 -2.049100e+02 +2 3464 7.025699e+02 4.484003e+01 +3 3464 9.412100e+02 1.704400e+02 +17 3464 -1.037860e+03 3.972500e+02 +2 3465 6.888700e+02 5.807001e+01 +3 3465 9.145300e+02 1.898900e+02 +2 3466 6.200000e+02 5.838000e+01 +3 3466 7.635000e+02 1.572700e+02 +2 3467 -3.748100e+02 5.903003e+01 +7 3467 1.798500e+02 3.151599e+02 +9 3467 -3.932500e+02 1.803600e+02 +11 3467 2.619700e+02 1.192700e+02 +2 3468 -5.277400e+02 5.881000e+01 +7 3468 8.678003e+01 3.144199e+02 +11 3468 1.513199e+02 1.161700e+02 +2 3469 -4.415300e+02 6.126001e+01 +7 3469 1.383400e+02 3.162200e+02 +9 3469 -4.444000e+02 1.805901e+02 +2 3470 -2.402100e+02 7.212000e+01 +7 3470 2.853600e+02 3.254800e+02 +9 3470 -2.814700e+02 1.979500e+02 +10 3470 -2.112000e+02 -4.005900e+02 +11 3470 3.641400e+02 1.365800e+02 +12 3470 -8.300800e+02 -5.123000e+02 +13 3470 -1.636390e+03 4.500701e+02 +20 3470 -3.794900e+02 -1.924800e+02 +2 3471 -2.402100e+02 7.212000e+01 +7 3471 2.853600e+02 3.254800e+02 +9 3471 -2.814700e+02 1.979500e+02 +13 3471 -1.636390e+03 4.500701e+02 +18 3471 -4.483600e+02 6.020020e+00 +2 3472 -4.314700e+02 9.795001e+01 +7 3472 1.442700e+02 3.384099e+02 +11 3472 2.194100e+02 1.459600e+02 +2 3473 -3.978600e+02 1.082100e+02 +7 3473 1.659399e+02 3.444700e+02 +9 3473 -4.095699e+02 2.165100e+02 +10 3473 -3.085300e+02 -3.823400e+02 +11 3473 2.445500e+02 1.543800e+02 +12 3473 -9.429300e+02 -4.953700e+02 +18 3473 -5.306400e+02 2.008997e+01 +20 3473 -4.506700e+02 -1.810699e+02 +2 3474 6.190601e+02 1.120000e+02 +3 3474 7.613600e+02 2.483301e+02 +17 3474 -1.177400e+03 5.015300e+02 +2 3475 3.845300e+02 1.135200e+02 +3 3475 3.178101e+02 6.332001e+01 +11 3475 9.057900e+02 2.202100e+02 +2 3476 4.397800e+02 1.354500e+02 +3 3476 3.881000e+02 9.326001e+01 +17 3476 -1.546060e+03 5.501200e+02 +2 3477 4.397800e+02 1.354500e+02 +3 3477 3.881000e+02 9.326001e+01 +17 3477 -1.546060e+03 5.501200e+02 +2 3478 -1.552900e+02 1.409600e+02 +3 3478 -5.497600e+02 3.036300e+02 +9 3478 -2.040500e+02 2.615300e+02 +10 3478 -1.508700e+02 -3.607600e+02 +11 3478 4.336300e+02 1.981900e+02 +13 3478 -1.363660e+03 6.245801e+02 +18 3478 -3.975200e+02 4.628003e+01 +20 3478 -3.359900e+02 -1.584200e+02 +2 3479 -7.928003e+01 1.525700e+02 +3 3479 -2.765500e+02 1.035900e+02 +9 3479 -9.632996e+01 3.148500e+02 +2 3480 5.581600e+02 1.643000e+02 +3 3480 6.343700e+02 2.945300e+02 +17 3480 -1.286770e+03 5.863201e+02 +2 3481 7.236100e+02 1.690900e+02 +6 3481 8.123199e+02 1.658000e+02 +2 3482 -1.535400e+02 1.686800e+02 +3 3482 -5.465100e+02 3.396300e+02 +11 3482 4.347400e+02 2.196100e+02 +13 3482 -1.356880e+03 6.862800e+02 +18 3482 -3.964000e+02 5.941992e+01 +20 3482 -3.352600e+02 -1.460601e+02 +2 3483 7.339000e+02 1.790800e+02 +3 3483 9.977900e+02 4.183400e+02 +2 3484 -1.625900e+02 1.926500e+02 +7 3484 3.555300e+02 4.000200e+02 +11 3484 4.267900e+02 2.351400e+02 +13 3484 -1.388490e+03 7.437700e+02 +2 3485 -4.380600e+02 1.950700e+02 +7 3485 1.397600e+02 3.959800e+02 +9 3485 -4.419000e+02 2.813301e+02 +11 3485 2.146600e+02 2.171900e+02 +2 3486 -3.301000e+02 2.080400e+02 +7 3486 2.110300e+02 4.053401e+02 +9 3486 -3.578101e+02 2.951500e+02 +11 3486 2.942900e+02 2.296300e+02 +18 3486 -4.963600e+02 6.805005e+01 +2 3487 -3.419800e+02 2.092700e+02 +7 3487 2.027500e+02 4.061300e+02 +11 3487 2.854900e+02 2.325800e+02 +2 3488 -3.803100e+02 2.107700e+02 +7 3488 1.783900e+02 4.061300e+02 +11 3488 2.566300e+02 2.301700e+02 +2 3489 6.951400e+02 2.126700e+02 +7 3489 8.748701e+02 4.181400e+02 +2 3490 -4.899700e+02 2.160600e+02 +7 3490 1.087400e+02 4.077100e+02 +9 3490 -4.812900e+02 2.966799e+02 +11 3490 1.772300e+02 2.302500e+02 +2 3491 -3.241400e+02 2.259100e+02 +7 3491 2.146600e+02 4.162700e+02 +9 3491 -3.531899e+02 3.094900e+02 +2 3492 -3.241400e+02 2.259100e+02 +7 3492 2.146600e+02 4.162700e+02 +18 3492 -4.934900e+02 7.690002e+01 +2 3493 7.802400e+02 2.341800e+02 +3 3493 1.087690e+03 5.177400e+02 +2 3494 4.534200e+02 2.881500e+02 +3 3494 4.050000e+02 2.887100e+02 +17 3494 -1.522620e+03 7.900500e+02 +2 3495 4.427500e+02 2.879400e+02 +3 3495 3.919000e+02 2.888401e+02 +17 3495 -1.541380e+03 7.904800e+02 +2 3496 -2.223600e+02 3.092300e+02 +7 3496 3.625601e+02 4.748201e+02 +10 3496 -1.731100e+02 -2.682100e+02 +11 3496 3.880000e+02 3.382000e+02 +12 3496 -7.694600e+02 -3.486300e+02 +13 3496 -1.458820e+03 1.035110e+03 +2 3497 -2.031200e+02 3.095700e+02 +3 3497 -5.596900e+02 4.784700e+02 +7 3497 3.741300e+02 4.751500e+02 +10 3497 -1.630100e+02 -2.673600e+02 +13 3497 -1.410510e+03 1.036310e+03 +2 3498 -2.121500e+02 3.097800e+02 +7 3498 3.687100e+02 4.748700e+02 +12 3498 -7.632900e+02 -3.486100e+02 +13 3498 -1.433160e+03 1.036640e+03 +2 3499 -5.431000e+02 3.266200e+02 +7 3499 7.884998e+01 4.733900e+02 +2 3500 -4.549800e+02 3.358900e+02 +6 3500 -7.800700e+02 4.521100e+02 +7 3500 1.311700e+02 4.799500e+02 +10 3500 -3.398000e+02 -2.596500e+02 +11 3500 2.028600e+02 3.194600e+02 +16 3500 3.353700e+02 4.512000e+02 +18 3500 -5.569200e+02 1.276899e+02 +2 3501 -4.507100e+02 3.430200e+02 +6 3501 -7.775300e+02 4.598000e+02 +9 3501 -4.523199e+02 3.948401e+02 +11 3501 2.051700e+02 3.245000e+02 +12 3501 -9.712400e+02 -3.548000e+02 +2 3502 -5.971100e+02 3.698200e+02 +7 3502 4.647998e+01 4.979600e+02 +9 3502 -5.653900e+02 4.132600e+02 +16 3502 2.703000e+02 4.629700e+02 +2 3503 -2.787600e+02 3.729700e+02 +7 3503 2.499800e+02 5.058500e+02 +11 3503 3.330100e+02 3.557600e+02 +2 3504 -3.678400e+02 3.824200e+02 +7 3504 1.859200e+02 5.094299e+02 +11 3504 2.656100e+02 3.565800e+02 +2 3505 -3.884300e+02 3.874800e+02 +4 3505 8.236399e+02 4.554700e+02 +7 3505 1.728000e+02 5.117800e+02 +10 3505 -3.022300e+02 -2.306400e+02 +11 3505 2.505400e+02 3.587500e+02 +18 3505 -5.240600e+02 1.528401e+02 +20 3505 -4.446300e+02 -6.648999e+01 +2 3506 -3.314400e+02 3.971600e+02 +7 3506 2.112000e+02 5.187100e+02 +9 3506 -3.598199e+02 4.403201e+02 +2 3507 -2.935700e+02 4.076400e+02 +7 3507 2.391400e+02 5.258401e+02 +10 3507 -2.469900e+02 -2.209500e+02 +12 3507 -8.658300e+02 -3.147700e+02 +2 3508 -5.452300e+02 4.185900e+02 +7 3508 7.809998e+01 5.283000e+02 +10 3508 -3.884800e+02 -2.153300e+02 +2 3509 -4.919200e+02 4.288000e+02 +7 3509 1.090601e+02 5.347500e+02 +9 3509 -4.853400e+02 4.593600e+02 +10 3509 -3.590601e+02 -2.103000e+02 +11 3509 1.748700e+02 3.857700e+02 +12 3509 -9.936200e+02 -3.041700e+02 +18 3509 -5.736500e+02 1.713500e+02 +2 3510 -6.294500e+02 4.434500e+02 +7 3510 2.994995e+01 5.410601e+02 +10 3510 -4.326200e+02 -2.028500e+02 +12 3510 -1.076950e+03 -2.933400e+02 +2 3511 5.800300e+02 4.440300e+02 +7 3511 8.906899e+02 5.716300e+02 +12 3511 -2.520000e+02 -2.670400e+02 +16 3511 9.858900e+02 5.449700e+02 +17 3511 -1.282860e+03 1.020830e+03 +2 3512 5.727600e+02 4.472300e+02 +7 3512 8.869099e+02 5.749100e+02 +12 3512 -2.558300e+02 -2.634700e+02 +17 3512 -1.291750e+03 1.028630e+03 +2 3513 -5.460000e+02 4.526100e+02 +7 3513 7.545996e+01 5.484700e+02 +11 3513 1.348400e+02 4.024600e+02 +2 3514 6.042500e+02 4.645000e+02 +3 3514 6.535900e+02 6.527500e+02 +12 3514 -2.340100e+02 -2.530800e+02 +2 3515 -4.115100e+02 4.657900e+02 +5 3515 3.123700e+02 9.123101e+02 +7 3515 1.579900e+02 5.585100e+02 +8 3515 -9.438600e+02 7.573199e+02 +10 3515 -3.156100e+02 -1.896000e+02 +11 3515 2.334200e+02 4.161700e+02 +20 3515 -4.539399e+02 -3.525000e+01 +2 3516 -4.213800e+02 4.833300e+02 +7 3516 1.509900e+02 5.687500e+02 +11 3516 2.257300e+02 4.285000e+02 +12 3516 -9.498600e+02 -2.714200e+02 +18 3516 -5.396600e+02 1.976000e+02 +2 3517 7.006100e+02 -2.406000e+02 +3 3517 9.430701e+02 -3.398199e+02 +2 3518 7.002000e+02 -2.311500e+02 +3 3518 9.427500e+02 -3.231400e+02 +2 3519 7.002000e+02 -2.311500e+02 +3 3519 9.427500e+02 -3.231400e+02 +2 3520 -4.423200e+02 -2.269200e+02 +7 3520 1.236899e+02 1.458401e+02 +20 3520 -4.738500e+02 -3.186000e+02 +2 3521 -2.704100e+02 -1.894200e+02 +3 3521 -8.765200e+02 -2.310601e+02 +9 3521 -3.070100e+02 -4.189941e+00 +10 3521 -2.339800e+02 -5.439600e+02 +11 3521 3.407600e+02 -5.925000e+01 +2 3522 -2.703600e+02 -1.818500e+02 +3 3522 -8.760100e+02 -2.164900e+02 +10 3522 -2.340200e+02 -5.399600e+02 +11 3522 3.412000e+02 -5.372998e+01 +2 3523 -2.226800e+02 -1.759800e+02 +3 3523 -7.363500e+02 -2.189100e+02 +9 3523 -2.651200e+02 8.979980e+00 +10 3523 -2.006000e+02 -5.364100e+02 +11 3523 3.786801e+02 -4.638000e+01 +13 3523 -1.598840e+03 -1.690800e+02 +18 3523 -4.411200e+02 -1.117500e+02 +20 3523 -3.737900e+02 -2.945000e+02 +2 3524 -2.357400e+02 -1.750000e+02 +3 3524 -7.706900e+02 -2.151899e+02 +7 3524 2.850400e+02 1.757500e+02 +11 3524 3.684000e+02 -4.608002e+01 +13 3524 -1.638680e+03 -1.638700e+02 +2 3525 -3.372100e+02 -1.748800e+02 +7 3525 2.034900e+02 1.761100e+02 +9 3525 -3.605200e+02 3.790039e+00 +11 3525 2.907700e+02 -5.058002e+01 +12 3525 -9.101100e+02 -6.666100e+02 +2 3526 -3.613900e+02 -1.695500e+02 +6 3526 -7.009900e+02 -1.905200e+02 +11 3526 2.722900e+02 -4.759003e+01 +12 3526 -9.263900e+02 -6.643500e+02 +18 3526 -5.149800e+02 -1.110900e+02 +2 3527 6.950400e+02 -1.471600e+02 +3 3527 9.313899e+02 -1.733500e+02 +6 3527 7.674200e+02 -2.440300e+02 +8 3527 7.568199e+02 -1.063300e+02 +2 3528 6.714500e+02 -1.046000e+02 +3 3528 8.740100e+02 -1.054600e+02 +2 3529 7.240900e+02 -9.948999e+01 +6 3529 8.061400e+02 -1.819800e+02 +17 3529 -1.007410e+03 1.783500e+02 +2 3530 -2.412500e+02 -9.642999e+01 +3 3530 -7.834200e+02 -6.915002e+01 +11 3530 3.636500e+02 1.150000e+01 +13 3530 -1.651160e+03 3.078003e+01 +2 3531 -2.801100e+02 -8.309998e+01 +7 3531 2.452400e+02 2.310100e+02 +9 3531 -3.153400e+02 7.572998e+01 +10 3531 -2.400699e+02 -4.860000e+02 +11 3531 3.328800e+02 1.826001e+01 +2 3532 -7.096997e+01 -6.979999e+01 +3 3532 -2.927900e+02 -1.572500e+02 +8 3532 2.333101e+02 -6.115002e+01 +10 3532 -6.285999e+01 -4.758700e+02 +11 3532 5.194500e+02 6.103998e+01 +13 3532 -9.854600e+02 6.218005e+01 +16 3532 6.909800e+02 2.734100e+02 +18 3532 -3.282300e+02 -4.425000e+01 +2 3533 -4.696900e+02 -6.992999e+01 +7 3533 1.200200e+02 2.385801e+02 +2 3534 -3.741300e+02 -6.491998e+01 +7 3534 1.794301e+02 2.415400e+02 +9 3534 -3.905300e+02 8.651001e+01 +2 3535 5.747000e+02 -6.435999e+01 +3 3535 6.709301e+02 -6.856000e+01 +17 3535 -1.257070e+03 2.323900e+02 +2 3536 -2.452500e+02 -3.789001e+01 +7 3536 2.790800e+02 2.576500e+02 +9 3536 -2.853600e+02 1.128199e+02 +10 3536 -2.156600e+02 -4.609301e+02 +11 3536 3.603900e+02 5.403998e+01 +12 3536 -8.382200e+02 -5.801200e+02 +18 3536 -4.528101e+02 -4.657996e+01 +20 3536 -3.837900e+02 -2.383199e+02 +2 3537 -2.417000e+02 -3.332001e+01 +3 3537 -7.853400e+02 5.062000e+01 +7 3537 2.804200e+02 2.610100e+02 +10 3537 -2.134500e+02 -4.583800e+02 +11 3537 3.631000e+02 5.790002e+01 +13 3537 -1.650610e+03 1.878800e+02 +2 3538 -2.104200e+02 -2.803998e+01 +3 3538 -6.953200e+02 3.896997e+01 +10 3538 -1.910699e+02 -4.557300e+02 +11 3538 3.884800e+02 6.488000e+01 +13 3538 -1.550720e+03 1.966500e+02 +20 3538 -3.658300e+02 -2.330699e+02 +2 3539 -2.433400e+02 -2.059998e+01 +7 3539 2.799800e+02 2.685901e+02 +10 3539 -2.143000e+02 -4.513199e+02 +11 3539 3.618700e+02 6.770001e+01 +12 3539 -8.357900e+02 -5.693500e+02 +13 3539 -1.653340e+03 2.193700e+02 +2 3540 -3.450400e+02 -1.720001e+01 +3 3540 -1.058700e+03 1.227400e+02 +7 3540 1.995500e+02 2.699700e+02 +10 3540 -2.792200e+02 -4.502100e+02 +2 3541 -1.878500e+02 -1.021997e+01 +7 3541 3.308400e+02 2.759800e+02 +9 3541 -2.348400e+02 1.394800e+02 +11 3541 4.065800e+02 7.965997e+01 +20 3541 -3.549600e+02 -2.236400e+02 +2 3542 -1.611000e+02 -2.559998e+00 +7 3542 3.602100e+02 2.787200e+02 +10 3542 -1.555300e+02 -4.427200e+02 +11 3542 4.288500e+02 8.753003e+01 +12 3542 -7.632300e+02 -5.551200e+02 +2 3543 -2.370700e+02 7.100220e-01 +7 3543 2.847500e+02 2.815200e+02 +9 3543 -2.792200e+02 1.432700e+02 +10 3543 -2.102200e+02 -4.397600e+02 +11 3543 3.665300e+02 8.348999e+01 +13 3543 -1.634130e+03 2.717300e+02 +18 3543 -4.479200e+02 -2.685999e+01 +2 3544 -4.731500e+02 1.679999e+01 +4 3544 7.747600e+02 2.794399e+02 +5 3544 3.101200e+02 6.245400e+02 +7 3544 1.188800e+02 2.898401e+02 +9 3544 -4.665300e+02 1.468301e+02 +11 3544 1.902500e+02 8.677002e+01 +20 3544 -4.826300e+02 -2.189900e+02 +2 3545 -2.337200e+02 3.201001e+01 +3 3545 -7.568800e+02 1.620000e+02 +7 3545 2.904200e+02 3.006799e+02 +10 3545 -2.071801e+02 -4.220200e+02 +11 3545 3.694301e+02 1.072200e+02 +12 3545 -8.260300e+02 -5.360100e+02 +13 3545 -1.619450e+03 3.495901e+02 +2 3546 3.648500e+02 3.421997e+01 +3 3546 2.911100e+02 -4.222998e+01 +17 3546 -1.669700e+03 3.941899e+02 +2 3547 -5.278000e+02 4.002002e+01 +6 3547 -9.145000e+02 9.133002e+01 +2 3548 5.789900e+02 5.251001e+01 +3 3548 6.805601e+02 1.284700e+02 +17 3548 -1.247270e+03 4.114299e+02 +2 3549 -2.889200e+02 5.766998e+01 +7 3549 2.400000e+02 3.157600e+02 +10 3549 -2.448700e+02 -4.089700e+02 +11 3549 3.261000e+02 1.217900e+02 +12 3549 -8.708600e+02 -5.242000e+02 +2 3550 -2.636700e+02 7.471002e+01 +7 3550 2.618800e+02 3.257000e+02 +9 3550 -3.027100e+02 1.975801e+02 +10 3550 -2.279500e+02 -3.995100e+02 +11 3550 3.464100e+02 1.357700e+02 +12 3550 -8.499300e+02 -5.126000e+02 +18 3550 -4.610000e+02 6.400024e+00 +20 3550 -3.905699e+02 -1.926500e+02 +2 3551 -2.636700e+02 7.471002e+01 +7 3551 2.618800e+02 3.257000e+02 +9 3551 -3.027100e+02 1.975801e+02 +10 3551 -2.279500e+02 -3.995100e+02 +11 3551 3.464100e+02 1.357700e+02 +12 3551 -8.499300e+02 -5.126000e+02 +18 3551 -4.610000e+02 6.400024e+00 +20 3551 -3.905699e+02 -1.926500e+02 +2 3552 -4.951800e+02 8.476001e+01 +7 3552 1.054301e+02 3.298301e+02 +2 3553 -2.723200e+02 9.278003e+01 +3 3553 -8.665300e+02 3.041100e+02 +10 3553 -2.335500e+02 -3.896300e+02 +11 3553 3.386899e+02 1.487800e+02 +12 3553 -8.570400e+02 -5.015900e+02 +18 3553 -4.667100e+02 1.519995e+01 +20 3553 -3.954700e+02 -1.851300e+02 +2 3554 -2.970500e+02 9.658997e+01 +3 3554 -9.331000e+02 3.282400e+02 +11 3554 3.196700e+02 1.497800e+02 +2 3555 -2.671700e+02 9.898999e+01 +7 3555 2.591100e+02 3.405701e+02 +10 3555 -2.302800e+02 -3.861600e+02 +11 3555 3.429399e+02 1.538800e+02 +12 3555 -8.527300e+02 -4.978700e+02 +18 3555 -4.637200e+02 1.805005e+01 +20 3555 -3.929500e+02 -1.825500e+02 +2 3556 -3.301600e+02 9.934998e+01 +7 3556 2.104301e+02 3.401200e+02 +10 3556 -2.695500e+02 -3.868199e+02 +11 3556 2.947600e+02 1.503000e+02 +12 3556 -8.991200e+02 -5.001600e+02 +18 3556 -4.968900e+02 1.658997e+01 +2 3557 3.920500e+02 1.007300e+02 +3 3557 3.269000e+02 4.814001e+01 +17 3557 -1.621850e+03 4.979000e+02 +2 3558 3.920500e+02 1.007300e+02 +3 3558 3.269000e+02 4.814001e+01 +2 3559 -3.326500e+02 1.051600e+02 +7 3559 2.096899e+02 3.431200e+02 +9 3559 -3.585000e+02 2.162400e+02 +10 3559 -2.710100e+02 -3.836000e+02 +11 3559 2.927300e+02 1.541300e+02 +12 3559 -9.004400e+02 -4.962400e+02 +2 3560 -4.602000e+02 1.091000e+02 +7 3560 1.268400e+02 3.440901e+02 +10 3560 -3.435000e+02 -3.812900e+02 +11 3560 1.993600e+02 1.534400e+02 +12 3560 -9.827400e+02 -4.940300e+02 +18 3560 -5.610600e+02 2.064001e+01 +20 3560 -4.767200e+02 -1.807300e+02 +2 3561 -2.510000e+02 1.175100e+02 +3 3561 -8.029400e+02 3.330500e+02 +10 3561 -2.188700e+02 -3.757900e+02 +11 3561 3.555800e+02 1.692000e+02 +12 3561 -8.384600e+02 -4.852000e+02 +13 3561 -1.668500e+03 5.646599e+02 +18 3561 -4.543700e+02 2.818005e+01 +2 3562 6.300000e+02 1.209800e+02 +3 3562 7.793500e+02 2.616200e+02 +17 3562 -1.161920e+03 5.152600e+02 +2 3563 -1.691300e+02 1.407200e+02 +4 3563 1.019180e+03 3.466799e+02 +6 3563 -2.197600e+02 1.098600e+02 +9 3563 -2.184000e+02 2.602900e+02 +11 3563 4.217000e+02 1.959500e+02 +18 3563 -4.065800e+02 4.402002e+01 +2 3564 7.349800e+02 1.565500e+02 +3 3564 1.002270e+03 3.690601e+02 +2 3565 -1.269900e+02 1.728600e+02 +3 3565 -4.594700e+02 2.869099e+02 +7 3565 4.089800e+02 3.895200e+02 +9 3565 -1.741899e+02 2.958800e+02 +10 3565 -1.254800e+02 -3.429301e+02 +11 3565 4.599700e+02 2.313000e+02 +13 3565 -1.244590e+03 6.867500e+02 +18 3565 -3.758000e+02 6.576001e+01 +20 3565 -3.178800e+02 -1.414301e+02 +2 3566 -2.982600e+02 1.752100e+02 +7 3566 2.335500e+02 3.860601e+02 +10 3566 -2.511500e+02 -3.450699e+02 +11 3566 3.181400e+02 2.076200e+02 +12 3566 -8.753800e+02 -4.527100e+02 +2 3567 -1.768500e+02 1.847300e+02 +7 3567 3.453300e+02 3.936500e+02 +13 3567 -1.432280e+03 7.230500e+02 +18 3567 -4.109000e+02 6.464001e+01 +2 3568 -2.123400e+02 1.952300e+02 +7 3568 3.109100e+02 3.992700e+02 +9 3568 -2.575100e+02 2.950200e+02 +10 3568 -1.921899e+02 -3.332500e+02 +11 3568 3.866500e+02 2.304600e+02 +13 3568 -1.544630e+03 7.539200e+02 +18 3568 -4.314301e+02 6.717993e+01 +2 3569 -4.451400e+02 1.955000e+02 +7 3569 1.353000e+02 3.962500e+02 +11 3569 2.095900e+02 2.163700e+02 +2 3570 6.273101e+02 1.960400e+02 +3 3570 7.741700e+02 3.896700e+02 +2 3571 -3.106700e+02 1.977800e+02 +7 3571 2.242700e+02 3.993101e+02 +2 3572 -4.312700e+02 2.010200e+02 +7 3572 1.442700e+02 3.996799e+02 +9 3572 -4.363900e+02 2.864600e+02 +11 3572 2.199000e+02 2.212900e+02 +2 3573 -3.886300e+02 2.057100e+02 +7 3573 1.711801e+02 4.027500e+02 +9 3573 -4.040200e+02 2.917500e+02 +11 3573 2.502600e+02 2.259100e+02 +2 3574 -2.884400e+02 2.111600e+02 +3 3574 -9.132300e+02 5.450701e+02 +7 3574 2.406600e+02 4.075601e+02 +9 3574 -3.244600e+02 2.997100e+02 +11 3574 3.257300e+02 2.342500e+02 +18 3574 -4.749399e+02 7.065002e+01 +2 3575 -2.982400e+02 2.120700e+02 +3 3575 -9.379800e+02 5.516200e+02 +11 3575 3.182300e+02 2.345400e+02 +2 3576 -4.080500e+02 2.141100e+02 +7 3576 1.613500e+02 4.070901e+02 +9 3576 -4.188700e+02 2.974399e+02 +11 3576 2.362400e+02 2.314900e+02 +2 3577 -3.037900e+02 2.151200e+02 +7 3577 2.293900e+02 4.097200e+02 +10 3577 -2.542400e+02 -3.237000e+02 +11 3577 3.219800e+02 2.359700e+02 +2 3578 -3.111600e+02 2.259700e+02 +7 3578 2.233500e+02 4.160300e+02 +11 3578 3.083300e+02 2.434500e+02 +18 3578 -4.869000e+02 7.668994e+01 +2 3579 5.322000e+02 2.427100e+02 +3 3579 5.568300e+02 3.413201e+02 +12 3579 -2.852100e+02 -3.922200e+02 +17 3579 -1.351460e+03 7.111000e+02 +2 3580 -2.782800e+02 2.700300e+02 +3 3580 -8.865300e+02 6.511000e+02 +9 3580 -3.172300e+02 3.474900e+02 +11 3580 3.334200e+02 2.787900e+02 +2 3581 4.361801e+02 2.757400e+02 +3 3581 3.824000e+02 2.737500e+02 +17 3581 -1.551000e+03 7.736400e+02 +2 3582 4.317000e+02 2.800500e+02 +3 3582 3.770800e+02 2.780601e+02 +9 3582 3.260699e+02 4.218301e+02 +17 3582 -1.557920e+03 7.795100e+02 +2 3583 4.409399e+02 2.817800e+02 +3 3583 3.889301e+02 2.808800e+02 +2 3584 4.342700e+02 2.861900e+02 +3 3584 3.799500e+02 2.863900e+02 +9 3584 3.278600e+02 4.262600e+02 +17 3584 -1.553840e+03 7.885400e+02 +2 3585 4.378700e+02 2.923400e+02 +3 3585 3.854800e+02 2.941200e+02 +9 3585 3.312900e+02 4.306300e+02 +17 3585 -1.546600e+03 7.972400e+02 +2 3586 -1.540700e+02 3.023200e+02 +3 3586 -5.242500e+02 5.246100e+02 +2 3587 -3.016900e+02 3.289300e+02 +7 3587 2.333300e+02 4.784199e+02 +9 3587 -3.354301e+02 3.896599e+02 +11 3587 3.161100e+02 3.209400e+02 +18 3587 -4.809100e+02 1.264299e+02 +2 3588 -3.121300e+02 3.305800e+02 +7 3588 2.246700e+02 4.793500e+02 +9 3588 -3.441100e+02 3.900901e+02 +11 3588 3.079100e+02 3.214500e+02 +18 3588 -4.867500e+02 1.269000e+02 +2 3589 -3.121300e+02 3.305800e+02 +7 3589 2.246700e+02 4.793500e+02 +9 3589 -3.441100e+02 3.900901e+02 +11 3589 3.079100e+02 3.214500e+02 +2 3590 -3.669100e+02 3.318300e+02 +7 3590 1.868400e+02 4.788301e+02 +9 3590 -3.877500e+02 3.885901e+02 +11 3590 2.667400e+02 3.192200e+02 +2 3591 -3.541300e+02 3.330600e+02 +7 3591 1.947300e+02 4.798900e+02 +2 3592 -3.595000e+02 3.572200e+02 +8 3592 -8.650900e+02 6.101100e+02 +18 3592 -5.103600e+02 1.386799e+02 +2 3593 -3.845200e+02 3.634800e+02 +4 3593 8.227700e+02 4.436100e+02 +5 3593 3.372800e+02 8.518300e+02 +7 3593 1.733500e+02 4.974199e+02 +8 3593 -9.116000e+02 6.198600e+02 +9 3593 -4.020300e+02 4.117000e+02 +10 3593 -3.013400e+02 -2.442800e+02 +11 3593 2.531500e+02 3.415100e+02 +18 3593 -5.223700e+02 1.413500e+02 +2 3594 -5.881800e+02 3.662300e+02 +7 3594 5.171997e+01 4.956899e+02 +10 3594 -4.119000e+02 -2.440601e+02 +2 3595 -6.157100e+02 3.665000e+02 +7 3595 3.593005e+01 4.950100e+02 +9 3595 -5.788300e+02 4.096200e+02 +10 3595 -4.270300e+02 -2.440699e+02 +12 3595 -1.072200e+03 -3.405500e+02 +18 3595 -6.335000e+02 1.423600e+02 +2 3596 -4.756600e+02 3.677700e+02 +7 3596 1.173800e+02 4.982700e+02 +9 3596 -4.728000e+02 4.129800e+02 +10 3596 -3.518199e+02 -2.424800e+02 +11 3596 1.871500e+02 3.413700e+02 +2 3597 -6.728000e+02 3.680200e+02 +7 3597 4.760010e+00 4.956899e+02 +9 3597 -6.218300e+02 4.110400e+02 +2 3598 -6.094700e+02 3.703400e+02 +7 3598 3.909998e+01 4.981100e+02 +9 3598 -5.736600e+02 4.131200e+02 +10 3598 -4.226300e+02 -2.419600e+02 +11 3598 9.041003e+01 3.407700e+02 +12 3598 -1.068120e+03 -3.380800e+02 +18 3598 -6.304900e+02 1.443600e+02 +2 3599 -6.316300e+02 3.707600e+02 +7 3599 2.671997e+01 4.977000e+02 +9 3599 -5.911200e+02 4.132200e+02 +11 3599 7.417004e+01 3.407900e+02 +2 3600 -4.696300e+02 4.222700e+02 +7 3600 1.215100e+02 5.310100e+02 +11 3600 1.906200e+02 3.819900e+02 +2 3601 -5.728400e+02 4.587600e+02 +7 3601 6.139001e+01 5.510601e+02 +2 3602 6.032100e+02 4.643000e+02 +3 3602 6.528199e+02 6.524299e+02 +2 3603 6.032100e+02 4.643000e+02 +3 3603 6.528199e+02 6.524299e+02 +12 3603 -2.340100e+02 -2.530800e+02 +2 3604 -6.165300e+02 4.708600e+02 +7 3604 4.044995e+01 5.579700e+02 +2 3605 -7.133300e+02 4.747700e+02 +7 3605 -1.628003e+01 5.584600e+02 +9 3605 -6.539400e+02 4.928700e+02 +10 3605 -4.764399e+02 -1.866600e+02 +2 3606 -5.606200e+02 4.776400e+02 +7 3606 6.795996e+01 5.627000e+02 +9 3606 -5.384300e+02 4.954600e+02 +2 3607 -5.606200e+02 4.776400e+02 +7 3607 6.795996e+01 5.627000e+02 +9 3607 -5.384300e+02 4.954600e+02 +12 3607 -1.035600e+03 -2.748300e+02 +2 3608 7.053101e+02 -2.003800e+02 +3 3608 9.505400e+02 -2.674000e+02 +2 3609 7.636300e+02 -1.723200e+02 +8 3609 8.316400e+02 -1.416000e+02 +2 3610 7.782400e+02 -1.675600e+02 +3 3610 1.099410e+03 -2.024900e+02 +2 3611 6.629700e+02 -1.469100e+02 +3 3611 8.593400e+02 -1.803400e+02 +2 3612 6.767800e+02 -1.378400e+02 +3 3612 8.915601e+02 -1.622600e+02 +2 3613 4.721100e+02 -1.226500e+02 +3 3613 4.602200e+02 -2.095601e+02 +17 3613 -1.457530e+03 1.458500e+02 +2 3614 4.725200e+02 -1.145600e+02 +3 3614 4.600400e+02 -1.987600e+02 +2 3615 -1.194300e+02 -1.030600e+02 +3 3615 -4.456100e+02 -1.504100e+02 +9 3615 -1.654100e+02 7.869995e+01 +2 3616 4.296801e+02 -8.429999e+01 +3 3616 3.905800e+02 -1.678000e+02 +2 3617 4.720100e+02 -8.275000e+01 +3 3617 4.587500e+02 -1.524900e+02 +2 3618 -6.860999e+01 -7.445001e+01 +3 3618 -2.887600e+02 -1.645600e+02 +11 3618 5.214600e+02 5.746002e+01 +13 3618 -9.775200e+02 5.002002e+01 +2 3619 4.307800e+02 -6.809998e+01 +3 3619 3.915800e+02 -1.458500e+02 +2 3620 7.144399e+02 -5.527002e+01 +3 3620 9.657000e+02 -7.289978e+00 +6 3620 7.954399e+02 -1.246700e+02 +17 3620 -1.020120e+03 2.436300e+02 +2 3621 5.834200e+02 -4.725000e+01 +3 3621 6.899500e+02 -3.246002e+01 +2 3622 6.596000e+02 -4.221002e+01 +3 3622 8.507600e+02 2.469971e+00 +2 3623 4.754301e+02 -4.162000e+01 +3 3623 4.640800e+02 -9.397998e+01 +17 3623 -1.452580e+03 2.717100e+02 +2 3624 -3.540900e+02 -3.734003e+01 +3 3624 -1.086740e+03 8.673999e+01 +11 3624 2.770900e+02 4.914001e+01 +2 3625 -2.625000e+02 -3.669000e+01 +7 3625 2.604500e+02 2.587500e+02 +9 3625 -3.008900e+02 1.125200e+02 +10 3625 -2.280900e+02 -4.603600e+02 +11 3625 3.466700e+02 5.362000e+01 +13 3625 -1.715040e+03 1.818500e+02 +18 3625 -4.627200e+02 -4.670996e+01 +2 3626 -2.141900e+02 -3.317999e+01 +3 3626 -7.047900e+02 3.165002e+01 +13 3626 -1.561200e+03 1.846400e+02 +2 3627 4.413000e+02 -2.857001e+01 +3 3627 4.108500e+02 -8.284998e+01 +11 3627 9.361200e+02 9.363000e+01 +2 3628 -2.271900e+02 -2.602002e+01 +7 3628 2.947700e+02 2.650200e+02 +11 3628 3.748700e+02 6.471002e+01 +13 3628 -1.603760e+03 2.025500e+02 +2 3629 4.637400e+02 -2.320001e+01 +3 3629 4.466500e+02 -6.825000e+01 +2 3630 -2.282800e+02 -1.002002e+01 +3 3630 -7.480400e+02 8.572998e+01 +11 3630 3.736100e+02 7.623999e+01 +13 3630 -1.607810e+03 2.450901e+02 +2 3631 4.365601e+02 2.640997e+01 +3 3631 4.015500e+02 -1.252002e+01 +2 3632 4.861700e+02 2.945001e+01 +3 3632 4.815200e+02 1.241998e+01 +17 3632 -1.433030e+03 3.812900e+02 +2 3633 6.221000e+02 3.626001e+01 +3 3633 7.663101e+02 1.193100e+02 +7 3633 8.470601e+02 3.053700e+02 +2 3634 -1.154400e+02 3.734003e+01 +7 3634 4.166100e+02 3.055701e+02 +11 3634 4.696000e+02 1.269100e+02 +2 3635 -2.832200e+02 4.359003e+01 +3 3635 -9.008900e+02 2.179000e+02 +11 3635 3.302900e+02 1.108400e+02 +2 3636 5.671000e+02 4.771002e+01 +3 3636 6.528600e+02 1.114400e+02 +17 3636 -1.270760e+03 4.072400e+02 +2 3637 6.411600e+02 5.103998e+01 +3 3637 8.015601e+02 1.483200e+02 +17 3637 -1.143060e+03 4.084700e+02 +2 3638 -2.928500e+02 5.339001e+01 +7 3638 2.364000e+02 3.125801e+02 +10 3638 -2.480400e+02 -4.110900e+02 +11 3638 3.227600e+02 1.180100e+02 +12 3638 -8.745700e+02 -5.265100e+02 +2 3639 -2.881900e+02 6.602002e+01 +3 3639 -9.158700e+02 2.681200e+02 +7 3639 2.401700e+02 3.198401e+02 +9 3639 -3.232400e+02 1.889500e+02 +10 3639 -2.445500e+02 -4.046100e+02 +11 3639 3.265900e+02 1.273800e+02 +12 3639 -8.703100e+02 -5.191600e+02 +2 3640 6.658600e+02 6.740002e+01 +3 3640 8.617400e+02 1.956400e+02 +17 3640 -1.099230e+03 4.316799e+02 +2 3641 -2.709000e+02 7.567999e+01 +3 3641 -8.660800e+02 2.747300e+02 +7 3641 2.554399e+02 3.261000e+02 +9 3641 -3.081300e+02 1.975601e+02 +10 3641 -2.329900e+02 -3.989301e+02 +11 3641 3.399399e+02 1.359800e+02 +12 3641 -8.564200e+02 -5.123600e+02 +18 3641 -4.661899e+02 7.050049e+00 +2 3642 -3.991400e+02 9.767999e+01 +7 3642 1.642300e+02 3.383401e+02 +11 3642 2.433300e+02 1.469000e+02 +2 3643 -3.991400e+02 9.767999e+01 +7 3643 1.642300e+02 3.383401e+02 +9 3643 -4.117400e+02 2.095100e+02 +11 3643 2.433300e+02 1.469000e+02 +2 3644 5.509600e+02 1.013100e+02 +3 3644 6.234600e+02 1.951200e+02 +17 3644 -1.298090e+03 4.890200e+02 +2 3645 6.939100e+02 1.037700e+02 +3 3645 9.245800e+02 2.755601e+02 +2 3646 -1.659700e+02 1.088400e+02 +3 3646 -5.766900e+02 2.482600e+02 +5 3646 6.254800e+02 7.332100e+02 +9 3646 -2.156000e+02 2.355801e+02 +10 3646 -1.586700e+02 -3.799600e+02 +11 3646 4.246400e+02 1.715900e+02 +12 3646 -7.660900e+02 -4.851600e+02 +18 3646 -4.040900e+02 2.872998e+01 +2 3647 3.612000e+01 1.237100e+02 +6 3647 6.030200e+02 -1.865500e+02 +2 3648 -1.735500e+02 1.344700e+02 +3 3648 -5.963400e+02 2.994500e+02 +11 3648 4.180100e+02 1.902300e+02 +2 3649 -2.504000e+02 1.344500e+02 +3 3649 -8.003700e+02 3.673101e+02 +7 3649 2.762300e+02 3.642500e+02 +9 3649 -2.905000e+02 2.461599e+02 +10 3649 -2.188199e+02 -3.702700e+02 +11 3649 3.564399e+02 1.825800e+02 +13 3649 -1.663930e+03 6.123600e+02 +2 3650 7.262400e+02 1.372300e+02 +6 3650 8.158199e+02 1.225100e+02 +2 3651 -1.189000e+02 1.723100e+02 +3 3651 -4.444900e+02 2.859399e+02 +2 3652 7.178800e+02 1.879100e+02 +6 3652 8.041600e+02 1.864200e+02 +2 3653 -3.174700e+02 1.976100e+02 +3 3653 -9.816800e+02 5.314100e+02 +6 3653 -5.780100e+02 2.577400e+02 +8 3653 -7.825900e+02 3.880800e+02 +2 3654 -4.879300e+02 2.051800e+02 +7 3654 1.104600e+02 4.015601e+02 +11 3654 1.792500e+02 2.224600e+02 +2 3655 -4.040800e+02 2.169900e+02 +7 3655 1.629500e+02 4.094700e+02 +11 3655 2.399200e+02 2.340500e+02 +2 3656 7.797800e+02 2.249700e+02 +3 3656 1.086830e+03 5.024200e+02 +2 3657 -3.471000e+02 2.806200e+02 +7 3657 1.983800e+02 4.481400e+02 +11 3657 2.813400e+02 2.818700e+02 +2 3658 -1.511000e+02 2.827900e+02 +3 3658 -5.200800e+02 4.948800e+02 +2 3659 5.084100e+02 2.902000e+02 +3 3659 5.159100e+02 3.977200e+02 +17 3659 -1.394190e+03 7.865000e+02 +2 3660 4.488101e+02 2.925000e+02 +3 3660 3.987100e+02 2.942100e+02 +2 3661 5.100900e+02 2.982000e+02 +3 3661 5.189600e+02 4.090100e+02 +2 3662 -2.218700e+02 3.159800e+02 +3 3662 -5.879200e+02 4.858000e+02 +13 3662 -1.457160e+03 1.049000e+03 +2 3663 -3.538900e+02 3.214900e+02 +7 3663 1.949301e+02 4.730200e+02 +10 3663 -2.833300e+02 -2.664301e+02 +11 3663 2.764301e+02 3.120300e+02 +12 3663 -9.098400e+02 -3.663600e+02 +2 3664 -3.585500e+02 3.372700e+02 +7 3664 1.916600e+02 4.825000e+02 +2 3665 -6.586300e+02 3.384400e+02 +7 3665 1.354004e+01 4.787700e+02 +2 3666 -3.391700e+02 3.585900e+02 +7 3666 2.044200e+02 4.955601e+02 +2 3667 -3.659200e+02 3.613100e+02 +7 3667 1.859500e+02 4.967200e+02 +11 3667 2.672100e+02 3.408600e+02 +2 3668 -7.425700e+02 3.615400e+02 +7 3668 -3.181995e+01 4.909399e+02 +9 3668 -6.736100e+02 4.065500e+02 +2 3669 -4.634900e+02 3.673500e+02 +7 3669 1.247500e+02 4.983500e+02 +9 3669 -4.632900e+02 4.124800e+02 +11 3669 1.956500e+02 3.413101e+02 +2 3670 6.326000e+02 4.435601e+02 +7 3670 9.271101e+02 5.733400e+02 +2 3671 -3.527500e+02 4.538700e+02 +7 3671 2.000400e+02 5.534700e+02 +9 3671 -3.763500e+02 4.853301e+02 +2 3672 -6.906000e+02 4.586700e+02 +7 3672 -4.040039e+00 5.489800e+02 +9 3672 -6.358700e+02 4.803900e+02 +11 3672 3.160999e+01 4.047600e+02 +2 3673 6.048000e+02 4.603400e+02 +3 3673 6.557500e+02 6.479000e+02 +2 3674 -6.336600e+02 4.708600e+02 +7 3674 3.079004e+01 5.577100e+02 +9 3674 -5.920400e+02 4.918301e+02 +2 3675 -1.046100e+02 -1.980200e+02 +3 3675 -4.102600e+02 -3.029600e+02 +9 3675 -1.503500e+02 4.949951e+00 +2 3676 -2.464300e+02 -1.829900e+02 +3 3676 -7.986200e+02 -2.281899e+02 +11 3676 3.597800e+02 -5.301001e+01 +13 3676 -1.670300e+03 -1.839000e+02 +2 3677 -2.499900e+02 -1.771400e+02 +3 3677 -8.097100e+02 -2.159800e+02 +9 3677 -2.883199e+02 5.939941e+00 +13 3677 -1.681620e+03 -1.692500e+02 +2 3678 7.061600e+02 -1.606000e+02 +3 3678 9.498601e+02 -1.959800e+02 +17 3678 -1.034390e+03 8.442004e+01 +2 3679 7.243000e+02 -9.132001e+01 +6 3679 8.080601e+02 -1.729500e+02 +2 3680 -2.603100e+02 -8.563000e+01 +3 3680 -8.353900e+02 -4.321997e+01 +9 3680 -2.981000e+02 7.618005e+01 +11 3680 3.490000e+02 1.781000e+01 +13 3680 -1.708090e+03 5.763000e+01 +2 3681 4.785601e+02 -7.953998e+01 +3 3681 4.686200e+02 -1.480900e+02 +2 3682 4.878800e+02 -7.677002e+01 +3 3682 4.842900e+02 -1.408700e+02 +17 3682 -1.429250e+03 2.165801e+02 +2 3683 4.878800e+02 -7.677002e+01 +3 3683 4.842900e+02 -1.408700e+02 +2 3684 4.295200e+02 -7.271997e+01 +3 3684 3.901801e+02 -1.530300e+02 +17 3684 -1.538060e+03 2.235901e+02 +2 3685 -2.470100e+02 -3.003998e+01 +7 3685 2.766400e+02 2.626100e+02 +9 3685 -2.866700e+02 1.192000e+02 +11 3685 3.590699e+02 6.007001e+01 +2 3686 7.004500e+02 -7.590027e+00 +3 3686 9.373899e+02 7.571002e+01 +6 3686 7.788900e+02 -6.420001e+01 +17 3686 -1.041920e+03 3.165200e+02 +2 3687 -1.740300e+02 -5.590027e+00 +7 3687 3.454399e+02 2.780000e+02 +11 3687 4.177700e+02 8.496002e+01 +2 3688 -2.588800e+02 5.060999e+01 +3 3688 -8.285400e+02 2.142000e+02 +11 3688 3.494301e+02 1.189300e+02 +2 3689 -1.763400e+02 5.454999e+01 +3 3689 -6.044900e+02 1.615300e+02 +9 3689 -2.241100e+02 1.925500e+02 +11 3689 4.159700e+02 1.304700e+02 +2 3690 5.406500e+02 7.078003e+01 +3 3690 5.989700e+02 1.319400e+02 +2 3691 -3.300200e+02 8.664001e+01 +7 3691 2.107900e+02 3.329600e+02 +11 3691 2.948400e+02 1.409800e+02 +2 3692 -2.494500e+02 8.727002e+01 +3 3692 -7.993100e+02 2.724000e+02 +9 3692 -2.895601e+02 2.089099e+02 +10 3692 -2.181300e+02 -3.936801e+02 +11 3692 3.565900e+02 1.465400e+02 +12 3692 -8.381500e+02 -5.051600e+02 +13 3692 -1.666060e+03 4.858101e+02 +18 3692 -4.538700e+02 1.234998e+01 +2 3693 -2.108700e+02 9.746997e+01 +7 3693 3.314301e+02 3.387000e+02 +9 3693 -2.549600e+02 2.228600e+02 +10 3693 -1.899900e+02 -3.868199e+02 +11 3693 3.881899e+02 1.595500e+02 +18 3693 -4.307200e+02 2.073999e+01 +2 3694 3.881300e+02 1.041600e+02 +3 3694 3.226801e+02 5.235999e+01 +2 3695 7.389700e+02 1.670700e+02 +3 3695 1.010610e+03 3.940200e+02 +17 3695 -9.802300e+02 5.801899e+02 +2 3696 -2.604400e+02 1.692500e+02 +3 3696 -8.374400e+02 4.436400e+02 +13 3696 -1.702140e+03 6.940300e+02 +2 3697 6.810100e+02 1.874800e+02 +3 3697 8.949000e+02 4.136899e+02 +2 3698 7.433700e+02 1.928300e+02 +3 3698 1.018500e+03 4.396300e+02 +2 3699 -3.049600e+02 1.960900e+02 +3 3699 -9.519100e+02 5.232300e+02 +11 3699 3.139000e+02 2.223600e+02 +2 3700 5.296200e+02 2.328000e+02 +3 3700 5.522400e+02 3.257800e+02 +2 3701 -3.508900e+02 2.416500e+02 +3 3701 -1.074380e+03 6.412700e+02 +7 3701 1.942700e+02 4.248401e+02 +8 3701 -8.651000e+02 4.541799e+02 +2 3702 7.890699e+02 2.470900e+02 +6 3702 8.967900e+02 2.716100e+02 +2 3703 -3.336300e+02 3.924500e+02 +7 3703 2.095400e+02 5.160200e+02 +2 3704 -4.845900e+02 5.524800e+02 +6 3704 -6.806100e+02 6.468300e+02 +2 3705 -5.871002e+01 -2.143100e+02 +3 3705 -2.705700e+02 -3.548700e+02 +2 3706 -2.617100e+02 -1.996300e+02 +3 3706 -8.475800e+02 -2.542500e+02 +2 3707 -2.432300e+02 -1.952100e+02 +3 3707 -7.899800e+02 -2.526400e+02 +2 3708 -2.467600e+02 -1.762400e+02 +3 3708 -8.007700e+02 -2.131500e+02 +9 3708 -2.863900e+02 9.010010e+00 +11 3708 3.594200e+02 -4.682001e+01 +13 3708 -1.672070e+03 -1.643500e+02 +2 3709 -2.685400e+02 -1.673900e+02 +3 3709 -8.715500e+02 -1.887100e+02 +2 3710 7.370500e+02 -1.301300e+02 +6 3710 8.226300e+02 -2.229000e+02 +2 3711 4.411000e+02 -1.244000e+02 +3 3711 4.102300e+02 -2.191100e+02 +17 3711 -1.514890e+03 1.438201e+02 +2 3712 7.563400e+02 -3.776001e+01 +3 3712 1.049500e+03 2.928998e+01 +17 3712 -9.540500e+02 2.691699e+02 +2 3713 4.517800e+02 -2.162000e+01 +3 3713 4.266200e+02 -7.091998e+01 +17 3713 -1.494880e+03 3.028800e+02 +2 3714 -1.761700e+02 1.959998e+01 +7 3714 3.447400e+02 2.934299e+02 +2 3715 -2.446200e+02 3.523999e+01 +3 3715 -7.881300e+02 1.793700e+02 +13 3715 -1.653730e+03 3.585100e+02 +2 3716 -5.965997e+01 5.684998e+01 +3 3716 -2.645600e+02 -5.499878e-01 +2 3717 7.166000e+02 6.490002e+01 +6 3717 8.011200e+02 2.782001e+01 +2 3718 -2.072900e+02 9.720001e+01 +7 3718 3.196899e+02 3.395500e+02 +13 3718 -1.525030e+03 5.082900e+02 +2 3719 -2.040300e+02 1.127100e+02 +3 3719 -6.669600e+02 2.762500e+02 +13 3719 -1.515700e+03 5.473900e+02 +2 3720 4.888101e+02 1.207100e+02 +3 3720 4.863300e+02 1.477400e+02 +17 3720 -1.427460e+03 5.233101e+02 +2 3721 6.730300e+02 1.356800e+02 +3 3721 8.766200e+02 3.177300e+02 +17 3721 -1.086720e+03 5.350801e+02 +2 3722 -1.232500e+02 1.377600e+02 +3 3722 -4.508000e+02 2.299800e+02 +2 3723 -2.691200e+02 1.393700e+02 +3 3723 -8.576800e+02 3.913300e+02 +2 3724 -2.326800e+02 1.570200e+02 +3 3724 -7.515100e+02 3.890601e+02 +13 3724 -1.609930e+03 6.609600e+02 +2 3725 7.123800e+02 1.831400e+02 +3 3725 9.567100e+02 4.162100e+02 +2 3726 -2.274600e+02 1.896800e+02 +3 3726 -7.448500e+02 4.508000e+02 +2 3727 6.608101e+02 2.029600e+02 +3 3727 8.547400e+02 4.354500e+02 +2 3728 -2.562100e+02 2.296300e+02 +3 3728 -8.396100e+02 5.690100e+02 +13 3728 -1.694690e+03 8.441600e+02 +2 3729 -2.879900e+02 2.971300e+02 +3 3729 -9.053000e+02 7.034900e+02 +2 3730 5.186400e+02 3.396900e+02 +3 3730 5.258900e+02 4.580300e+02 +2 3731 -1.878900e+02 3.597800e+02 +3 3731 -4.086400e+02 3.591700e+02 +2 3732 -1.878900e+02 3.597800e+02 +3 3732 -4.086400e+02 3.591700e+02 +2 3733 5.375500e+02 4.348201e+02 +3 3733 5.499200e+02 5.882800e+02 +2 3734 5.375500e+02 4.348201e+02 +3 3734 5.499200e+02 5.882800e+02 +3 3735 -9.198100e+02 6.740400e+02 +7 3735 2.383800e+02 4.491799e+02 +9 3735 -3.291801e+02 3.533101e+02 +10 3735 -2.470500e+02 -2.890500e+02 +3 3736 7.641300e+02 -1.704200e+02 +6 3736 7.000601e+02 -2.401500e+02 +3 3737 -5.282700e+02 3.545701e+02 +7 3737 3.775400e+02 3.928000e+02 +9 3737 -1.979100e+02 2.965400e+02 +10 3737 -1.460100e+02 -3.375500e+02 +11 3737 4.397300e+02 2.316000e+02 +18 3737 -3.926400e+02 6.591992e+01 +20 3737 -3.321300e+02 -1.411000e+02 +3 3738 7.859301e+02 -3.813900e+02 +6 3738 7.101300e+02 -3.917800e+02 +3 3739 7.849600e+02 -3.432600e+02 +6 3739 7.102100e+02 -3.652200e+02 +3 3740 1.066450e+03 -1.788900e+02 +8 3740 8.257000e+02 -1.163800e+02 +3 3741 -5.318700e+02 2.038101e+02 +7 3741 3.746700e+02 3.440000e+02 +10 3741 -1.465200e+02 -3.853101e+02 +12 3741 -7.497500e+02 -4.877300e+02 +13 3741 -1.343880e+03 5.012800e+02 +18 3741 -3.942300e+02 2.572998e+01 +3 3742 -8.544200e+02 3.137300e+02 +7 3742 2.591100e+02 3.405701e+02 +3 3743 -3.182400e+02 1.028100e+02 +8 3743 3.098000e+02 1.868300e+02 +3 3744 1.088330e+03 2.788600e+02 +8 3744 8.571000e+02 2.644500e+02 +3 3745 -4.744700e+02 2.970400e+02 +7 3745 4.022500e+02 3.913500e+02 +10 3745 -1.295000e+02 -3.422900e+02 +13 3745 -1.263670e+03 6.911600e+02 +18 3745 -3.794600e+02 6.539001e+01 +3 3746 5.818500e+02 -5.070500e+02 +6 3746 -7.969000e+01 -4.405900e+02 +3 3747 -7.472500e+02 -3.541300e+02 +6 3747 -4.076500e+02 -3.162600e+02 +3 3748 -2.277400e+02 -2.608300e+02 +6 3748 4.067000e+02 -2.901300e+02 +10 3748 -1.808997e+01 -4.780300e+02 +13 3748 -8.082800e+02 7.099976e+00 +18 3748 -2.968800e+02 -2.063000e+01 +3 3749 -2.277400e+02 -2.608300e+02 +6 3749 4.067000e+02 -2.901300e+02 +10 3749 -1.808997e+01 -4.780300e+02 +13 3749 -8.082800e+02 7.099976e+00 +3 3750 -6.819600e+02 2.257600e+02 +7 3750 3.164200e+02 3.322300e+02 +3 3751 1.072020e+03 2.405500e+02 +6 3751 8.661400e+02 5.365997e+01 +17 3751 -9.335600e+02 4.447600e+02 +3 3752 7.448900e+02 3.892000e+02 +8 3752 7.130000e+02 3.720000e+02 +17 3752 -1.193180e+03 6.313800e+02 +3 3753 -9.224100e+02 8.102600e+02 +7 3753 2.375300e+02 4.898500e+02 +3 3754 -2.665300e+02 -3.860699e+02 +8 3754 2.721100e+02 -2.653800e+02 +3 3755 -2.665300e+02 -3.860699e+02 +8 3755 2.721100e+02 -2.653800e+02 +3 3756 -2.369800e+02 -2.586801e+02 +6 3756 3.981000e+02 -2.881000e+02 +10 3756 -2.343005e+01 -4.770900e+02 +13 3756 -8.333300e+02 1.214001e+01 +16 3756 8.600300e+02 2.748500e+02 +18 3756 -3.019500e+02 -2.021997e+01 +20 3756 -2.575000e+02 -2.137400e+02 +3 3757 -2.313900e+02 -2.525100e+02 +6 3757 4.034399e+02 -2.835400e+02 +10 3757 -2.013000e+01 -4.732300e+02 +13 3757 -8.180800e+02 2.810999e+01 +16 3757 8.646500e+02 2.788900e+02 +18 3757 -2.991400e+02 -1.614001e+01 +20 3757 -2.551300e+02 -2.102000e+02 +3 3758 5.302600e+02 -2.442200e+02 +6 3758 -9.447998e+01 -2.616800e+02 +3 3759 -1.949600e+02 -2.425900e+02 +6 3759 4.369200e+02 -2.789300e+02 +9 3759 -4.355005e+01 1.810500e+02 +10 3759 1.839966e+00 -4.655400e+02 +13 3759 -7.195200e+02 5.771997e+01 +18 3759 -2.778900e+02 -7.819946e+00 +20 3759 -2.371801e+02 -2.028700e+02 +3 3760 7.697300e+02 1.127002e+01 +6 3760 7.074200e+02 -1.097000e+02 +17 3760 -1.172380e+03 2.870701e+02 +3 3761 1.096710e+03 9.172998e+01 +7 3761 9.213899e+02 2.790100e+02 +17 3761 -9.152200e+02 3.193700e+02 +3 3762 1.096710e+03 9.172998e+01 +8 3762 8.621899e+02 1.099600e+02 +17 3762 -9.152200e+02 3.193700e+02 +3 3763 -6.808400e+02 2.796599e+02 +6 3763 -3.046600e+02 9.457001e+01 +3 3764 -5.902200e+02 3.359600e+02 +6 3764 -2.234500e+02 1.313200e+02 +13 3764 -1.415600e+03 6.628400e+02 +3 3765 9.697500e+02 3.635300e+02 +6 3765 8.068000e+02 1.423700e+02 +3 3766 1.098350e+03 4.563600e+02 +8 3766 8.689301e+02 4.118500e+02 +3 3767 -8.873300e+02 5.172200e+02 +6 3767 -5.034100e+02 2.489800e+02 +3 3768 5.710100e+02 -6.521400e+02 +6 3768 -9.592999e+01 -5.387500e+02 +3 3769 9.552200e+02 -4.850100e+02 +6 3769 7.772000e+02 -4.732800e+02 +3 3770 5.997000e+02 -4.559301e+02 +6 3770 -6.145001e+01 -4.066899e+02 +3 3771 5.812500e+02 -4.483000e+02 +6 3771 -7.316998e+01 -4.004900e+02 +3 3772 -7.211400e+02 -3.519100e+02 +6 3772 -3.849700e+02 -3.158700e+02 +13 3772 -1.581820e+03 -3.457600e+02 +3 3773 -2.260500e+02 -2.482600e+02 +6 3773 4.084700e+02 -2.804200e+02 +13 3773 -8.032500e+02 4.115002e+01 +18 3773 -2.957100e+02 -1.318994e+01 +3 3774 -2.350900e+02 -2.446200e+02 +6 3774 4.014399e+02 -2.772100e+02 +13 3774 -8.276900e+02 4.528003e+01 +3 3775 -2.887600e+02 -1.645600e+02 +8 3775 2.429301e+02 -6.657001e+01 +10 3775 -6.108997e+01 -4.784200e+02 +12 3775 -6.351500e+02 -5.793199e+02 +13 3775 -9.775200e+02 5.002002e+01 +3 3776 7.508000e+02 3.493700e+02 +6 3776 7.008800e+02 1.323300e+02 +3 3777 7.508000e+02 3.493700e+02 +6 3777 7.008800e+02 1.323300e+02 +3 3778 9.498201e+02 5.254299e+02 +8 3778 8.063400e+02 4.781600e+02 +3 3779 -1.070800e+03 7.599100e+02 +8 3779 -8.555200e+02 5.389700e+02 +3 3780 6.058600e+02 -2.925800e+02 +6 3780 -4.897998e+01 -2.957300e+02 +3 3781 -2.373900e+02 -2.800500e+02 +6 3781 3.969100e+02 -3.031800e+02 +3 3782 -2.098700e+02 -2.626100e+02 +6 3782 4.216801e+02 -2.923000e+02 +13 3782 -7.612100e+02 4.260010e+00 +3 3783 -6.625900e+02 -2.298101e+02 +6 3783 -3.112200e+02 -2.387200e+02 +3 3784 1.092550e+03 -1.594800e+02 +6 3784 8.705601e+02 -2.381500e+02 +3 3785 9.568999e+02 2.665002e+01 +6 3785 7.881200e+02 -9.983002e+01 +3 3786 1.100150e+03 3.820001e+01 +6 3786 8.812800e+02 -9.344000e+01 +3 3787 -3.137200e+02 7.991998e+01 +6 3787 2.002300e+02 -4.701001e+01 +3 3788 1.097770e+03 3.144900e+02 +6 3788 8.818101e+02 1.074500e+02 +3 3789 1.003370e+03 4.264800e+02 +8 3789 8.048199e+02 3.876600e+02 +3 3790 -6.117300e+02 4.810500e+02 +6 3790 -2.355400e+02 2.253300e+02 +3 3791 -6.117300e+02 4.810500e+02 +6 3791 -2.355400e+02 2.253300e+02 +3 3792 -2.170700e+02 -2.715200e+02 +6 3792 4.150100e+02 -2.973100e+02 +13 3792 -7.808200e+02 -1.954004e+01 +3 3793 -2.064200e+02 -2.203600e+02 +6 3793 4.255500e+02 -2.623900e+02 +13 3793 -7.493400e+02 1.146300e+02 +3 3794 -4.213400e+02 3.563700e+02 +8 3794 2.347700e+02 4.238000e+02 +3 3795 7.941100e+02 6.203400e+02 +6 3795 8.809800e+02 3.271500e+02 +3 3796 -2.060700e+02 -2.637500e+02 +6 3796 4.246899e+02 -2.942300e+02 +13 3796 -7.516000e+02 1.700439e-01 +3 3797 -5.015400e+02 1.898201e+02 +6 3797 -1.268800e+02 3.260999e+01 +8 3797 -2.166100e+02 1.971900e+02 +13 3797 -1.302720e+03 4.936000e+02 +4 3798 9.152400e+02 3.668000e+02 +5 3798 4.759399e+02 7.632900e+02 +4 3799 4.623700e+02 5.069000e+02 +7 3799 -4.139400e+02 6.027400e+02 +10 3799 -8.866500e+02 -1.358800e+02 +14 3799 2.006400e+02 3.614600e+02 +16 3799 -4.017999e+01 5.280701e+02 +19 3799 1.264230e+03 5.585900e+02 +4 3800 9.140601e+02 2.860500e+02 +5 3800 4.905300e+02 6.571899e+02 +4 3801 8.897900e+02 4.007200e+02 +5 3801 4.355100e+02 8.061500e+02 +4 3802 4.188400e+02 4.815200e+02 +7 3802 -4.682300e+02 5.729100e+02 +9 3802 -1.380330e+03 5.510200e+02 +10 3802 -9.393600e+02 -1.625601e+02 +11 3802 -6.786100e+02 4.686899e+02 +14 3802 1.678900e+02 3.425500e+02 +16 3802 -8.123999e+01 5.022500e+02 +18 3802 -1.127480e+03 2.433900e+02 +19 3802 1.188000e+03 5.072800e+02 +20 3802 -9.697800e+02 8.690002e+00 +4 3803 8.674299e+02 2.711599e+02 +5 3803 4.310400e+02 6.320300e+02 +10 3803 -2.592200e+02 -4.442300e+02 +12 3803 -8.881900e+02 -5.658700e+02 +4 3804 8.885601e+02 2.837500e+02 +5 3804 4.567400e+02 6.495300e+02 +4 3805 -5.704004e+01 3.020100e+02 +7 3805 -8.755500e+02 3.374600e+02 +4 3806 -3.368994e+01 3.409700e+02 +7 3806 -9.501800e+02 3.978700e+02 +15 3806 7.100900e+02 2.044800e+02 +16 3806 -4.902200e+02 3.591300e+02 +4 3807 9.155801e+02 3.452900e+02 +5 3807 4.798500e+02 7.384700e+02 +4 3808 1.156960e+03 3.823401e+02 +8 3808 -6.619995e+00 2.926400e+02 +4 3809 8.369800e+02 4.532600e+02 +5 3809 3.560699e+02 8.669800e+02 +4 3810 4.412200e+02 4.818700e+02 +7 3810 -4.342900e+02 5.671700e+02 +14 3810 1.876900e+02 3.373800e+02 +16 3810 -5.714001e+01 5.008201e+02 +19 3810 1.232340e+03 5.067200e+02 +20 3810 -9.392100e+02 5.429993e+00 +4 3811 4.979500e+02 5.264299e+02 +7 3811 -3.714200e+02 6.245800e+02 +9 3811 -1.249790e+03 6.212800e+02 +11 3811 -5.592000e+02 5.318400e+02 +14 3811 2.234900e+02 3.711300e+02 +18 3811 -1.043590e+03 2.840300e+02 +19 3811 1.324490e+03 5.903400e+02 +4 3812 4.895996e+01 5.671000e+02 +7 3812 -8.380600e+02 7.280900e+02 +10 3812 -1.224660e+03 -7.369995e+00 +15 3812 8.050601e+02 4.625701e+02 +16 3812 -4.109500e+02 6.035400e+02 +19 3812 5.727600e+02 7.342300e+02 +4 3813 2.497998e+01 2.519800e+02 +7 3813 -8.648000e+02 2.577100e+02 +10 3813 -1.274090e+03 -4.532600e+02 +14 3813 -6.866000e+01 1.954500e+02 +15 3813 7.771100e+02 1.020600e+02 +16 3813 -4.237900e+02 2.626200e+02 +4 3814 6.328003e+01 2.599399e+02 +7 3814 -8.186800e+02 2.692200e+02 +14 3814 -4.012000e+01 2.005200e+02 +15 3814 8.177600e+02 1.113400e+02 +16 3814 -3.873300e+02 2.731899e+02 +4 3815 6.328003e+01 2.599399e+02 +7 3815 -8.186800e+02 2.692200e+02 +10 3815 -1.235920e+03 -4.440100e+02 +14 3815 -4.012000e+01 2.005200e+02 +15 3815 8.177600e+02 1.113400e+02 +16 3815 -3.873300e+02 2.731899e+02 +4 3816 3.768005e+01 2.617700e+02 +7 3816 -8.509500e+02 2.701899e+02 +14 3816 -5.939999e+01 2.019300e+02 +15 3816 7.904200e+02 1.114600e+02 +16 3816 -4.129600e+02 2.726000e+02 +4 3817 -3.368994e+01 2.618600e+02 +7 3817 -9.477300e+02 2.765601e+02 +14 3817 -1.172200e+02 2.088400e+02 +16 3817 -4.872000e+02 2.736899e+02 +4 3818 -1.977700e+02 2.606599e+02 +5 3818 -9.997300e+02 4.014199e+02 +14 3818 -2.625600e+02 2.139100e+02 +16 3818 -6.681900e+02 2.698201e+02 +4 3819 -1.977700e+02 2.606599e+02 +5 3819 -9.997300e+02 4.014199e+02 +14 3819 -2.625600e+02 2.139100e+02 +4 3820 6.331006e+01 2.819199e+02 +7 3820 -8.195000e+02 3.071699e+02 +15 3820 8.176600e+02 1.400200e+02 +4 3821 6.331006e+01 2.819199e+02 +7 3821 -9.055100e+02 3.065300e+02 +4 3822 8.268994e+01 3.005601e+02 +7 3822 -7.937400e+02 3.350300e+02 +14 3822 -2.403000e+01 2.379800e+02 +15 3822 8.403900e+02 1.597400e+02 +16 3822 -3.694300e+02 3.183500e+02 +4 3823 1.100490e+03 3.791400e+02 +8 3823 -1.408400e+02 3.132800e+02 +4 3824 7.832800e+02 3.803201e+02 +7 3824 1.272600e+02 4.196599e+02 +16 3824 3.323400e+02 4.049500e+02 +4 3825 8.630901e+02 4.517700e+02 +5 3825 3.880100e+02 8.685500e+02 +8 3825 -7.914200e+02 6.315800e+02 +4 3826 4.522300e+02 5.135200e+02 +7 3826 -4.276000e+02 6.118400e+02 +9 3826 -1.322780e+03 6.006000e+02 +14 3826 1.925800e+02 3.640800e+02 +18 3826 -1.091140e+03 2.732200e+02 +19 3826 1.244740e+03 5.634900e+02 +4 3827 2.782996e+01 2.227100e+02 +7 3827 -8.585400e+02 2.150000e+02 +15 3827 7.803300e+02 6.854999e+01 +16 3827 -4.193400e+02 2.307900e+02 +4 3828 -3.518005e+01 2.492900e+02 +7 3828 -9.490300e+02 2.570000e+02 +15 3828 7.080200e+02 1.011100e+02 +4 3829 1.267770e+03 2.534299e+02 +8 3829 2.329800e+02 -4.187000e+01 +4 3830 1.308320e+03 2.647000e+02 +8 3830 3.107200e+02 -2.087000e+01 +16 3830 7.163700e+02 2.937100e+02 +4 3831 1.281680e+03 2.889299e+02 +8 3831 2.570699e+02 3.912000e+01 +4 3832 1.268830e+03 2.898900e+02 +8 3832 2.325699e+02 4.315002e+01 +16 3832 6.917100e+02 3.152900e+02 +4 3833 -1.985500e+02 2.886000e+02 +5 3833 -1.006580e+03 4.337400e+02 +16 3833 -6.702500e+02 2.990000e+02 +4 3834 1.156180e+03 3.154099e+02 +8 3834 -7.390015e+00 1.397300e+02 +16 3834 6.208900e+02 3.395900e+02 +4 3835 1.120720e+03 3.263900e+02 +5 3835 7.551899e+02 7.391600e+02 +8 3835 -8.845001e+01 1.819300e+02 +4 3836 8.931699e+02 3.595300e+02 +5 3836 4.478300e+02 7.517400e+02 +4 3837 9.606006e+01 4.094700e+02 +7 3837 -7.830900e+02 4.932100e+02 +15 3837 8.554800e+02 2.877200e+02 +16 3837 -3.609200e+02 4.354200e+02 +19 3837 6.589800e+02 4.328900e+02 +4 3838 9.606006e+01 4.094700e+02 +7 3838 -7.830900e+02 4.932100e+02 +10 3838 -1.190450e+03 -2.269900e+02 +16 3838 -3.609200e+02 4.354200e+02 +19 3838 6.589800e+02 4.328900e+02 +4 3839 7.810999e+01 4.294700e+02 +7 3839 -8.848500e+02 5.319800e+02 +4 3840 3.536000e+02 4.321400e+02 +7 3840 -5.828600e+02 5.053800e+02 +10 3840 -1.060870e+03 -2.247200e+02 +14 3840 1.049600e+02 3.033000e+02 +16 3840 -1.562400e+02 4.497400e+02 +19 3840 1.053440e+03 4.037500e+02 +4 3841 4.518000e+02 5.265601e+02 +7 3841 -4.271500e+02 6.329000e+02 +9 3841 -1.329490e+03 6.303900e+02 +11 3841 -6.270600e+02 5.391899e+02 +14 3841 1.926700e+02 3.731600e+02 +16 3841 -4.976001e+01 5.472500e+02 +4 3842 -2.198300e+02 2.325100e+02 +5 3842 -1.020890e+03 3.587600e+02 +14 3842 -2.855200e+02 1.886300e+02 +15 3842 4.933199e+02 8.348999e+01 +16 3842 -6.959400e+02 2.351500e+02 +4 3843 6.593994e+01 2.476699e+02 +7 3843 -8.149600e+02 2.525901e+02 +10 3843 -1.233070e+03 -4.583199e+02 +14 3843 -3.878000e+01 1.897900e+02 +15 3843 8.218199e+02 9.756000e+01 +16 3843 -3.850300e+02 2.601400e+02 +4 3844 -1.970400e+02 2.488000e+02 +5 3844 -9.983100e+02 3.859800e+02 +15 3844 5.210300e+02 1.016700e+02 +16 3844 -6.672900e+02 2.550900e+02 +19 3844 1.103300e+02 1.345400e+02 +4 3845 1.257040e+03 2.826500e+02 +8 3845 2.098101e+02 2.798999e+01 +4 3846 1.257040e+03 2.826500e+02 +8 3846 2.098101e+02 2.798999e+01 +4 3847 1.142000e+02 2.839800e+02 +7 3847 -7.610500e+02 3.092200e+02 +10 3847 -1.182730e+03 -4.035699e+02 +14 3847 -4.839996e+00 2.199100e+02 +15 3847 8.720800e+02 1.428100e+02 +16 3847 -3.398000e+02 3.019100e+02 +4 3848 1.197300e+02 2.937400e+02 +7 3848 -8.067100e+02 3.247300e+02 +4 3849 1.142930e+03 3.158700e+02 +8 3849 -3.504999e+01 1.450700e+02 +4 3850 9.257200e+02 3.346799e+02 +5 3850 4.964399e+02 7.238400e+02 +4 3851 8.536399e+02 3.614299e+02 +7 3851 2.070400e+02 3.914199e+02 +12 3851 -9.003900e+02 -4.477600e+02 +18 3851 -4.991800e+02 5.767993e+01 +20 3851 -4.231300e+02 -1.482700e+02 +4 3852 4.270300e+02 4.266899e+02 +7 3852 -4.575000e+02 4.936799e+02 +9 3852 -1.360200e+03 4.378500e+02 +10 3852 -9.303900e+02 -2.371400e+02 +11 3852 -6.587100e+02 3.610000e+02 +16 3852 -7.116998e+01 4.450900e+02 +4 3853 3.632400e+02 4.318900e+02 +7 3853 -5.651900e+02 5.050000e+02 +14 3853 1.141100e+02 3.031300e+02 +16 3853 -1.446400e+02 4.499100e+02 +18 3853 -1.229420e+03 1.861400e+02 +19 3853 1.072760e+03 4.062200e+02 +4 3854 3.632400e+02 4.318900e+02 +7 3854 -5.651900e+02 5.050000e+02 +16 3854 -1.446400e+02 4.499100e+02 +18 3854 -1.229420e+03 1.861400e+02 +4 3855 1.155100e+02 4.336300e+02 +7 3855 -7.595900e+02 5.236799e+02 +14 3855 8.500061e-01 3.447000e+02 +15 3855 8.759600e+02 3.106799e+02 +16 3855 -3.422500e+02 4.580100e+02 +19 3855 6.941299e+02 4.746899e+02 +4 3856 2.921997e+01 4.340701e+02 +7 3856 -8.614700e+02 5.306899e+02 +14 3856 -6.014999e+01 3.546200e+02 +16 3856 -4.273000e+02 4.596600e+02 +19 3856 5.387000e+02 4.846599e+02 +4 3857 3.787700e+02 4.364399e+02 +7 3857 -5.368400e+02 5.105100e+02 +9 3857 -1.489300e+03 4.650601e+02 +11 3857 -7.810000e+02 3.859000e+02 +14 3857 1.298700e+02 3.072700e+02 +18 3857 -1.197700e+03 1.890901e+02 +19 3857 1.105710e+03 4.185200e+02 +4 3858 3.787700e+02 4.364399e+02 +7 3858 -5.368400e+02 5.105100e+02 +4 3859 3.949100e+02 4.409500e+02 +7 3859 -5.066900e+02 5.156799e+02 +9 3859 -1.437150e+03 4.699900e+02 +11 3859 -7.313800e+02 3.901400e+02 +14 3859 1.465400e+02 3.111700e+02 +16 3859 -1.066700e+02 4.590500e+02 +18 3859 -1.165320e+03 1.905300e+02 +19 3859 1.140620e+03 4.315701e+02 +4 3860 3.325800e+02 4.427000e+02 +7 3860 -6.295100e+02 5.220801e+02 +14 3860 8.128003e+01 3.103900e+02 +19 3860 1.005420e+03 4.153500e+02 +4 3861 3.325800e+02 4.427000e+02 +7 3861 -6.295100e+02 5.220801e+02 +16 3861 -1.842300e+02 4.602400e+02 +19 3861 1.005420e+03 4.153500e+02 +4 3862 -6.680054e+00 4.435801e+02 +7 3862 -9.122700e+02 5.480100e+02 +10 3862 -1.304490e+03 -1.717400e+02 +14 3862 -9.000000e+01 3.666700e+02 +16 3862 -4.659400e+02 4.708700e+02 +19 3862 4.707400e+02 5.045601e+02 +20 3862 -1.206120e+03 -3.187000e+01 +4 3863 3.483400e+02 4.480100e+02 +7 3863 -6.002000e+02 5.278101e+02 +14 3863 9.629999e+01 3.141600e+02 +16 3863 -1.655300e+02 4.655800e+02 +19 3863 1.037730e+03 4.280300e+02 +4 3864 4.545200e+02 4.635601e+02 +7 3864 -4.040400e+02 5.405801e+02 +9 3864 -1.272470e+03 5.049600e+02 +11 3864 -5.761300e+02 4.233800e+02 +18 3864 -1.060160e+03 2.091799e+02 +4 3865 4.570699e+02 4.872400e+02 +7 3865 -4.098400e+02 5.753300e+02 +9 3865 -1.286370e+03 5.499700e+02 +10 3865 -8.810100e+02 -1.635400e+02 +11 3865 -5.891000e+02 4.667200e+02 +14 3865 2.014500e+02 3.458600e+02 +16 3865 -4.041998e+01 5.064900e+02 +18 3865 -1.068490e+03 2.403401e+02 +19 3865 1.261500e+03 5.213900e+02 +20 3865 -9.177500e+02 6.859985e+00 +4 3866 -4.229004e+01 5.045000e+02 +7 3866 -9.627800e+02 6.418500e+02 +15 3866 7.026200e+02 3.907800e+02 +4 3867 4.816000e+02 5.273700e+02 +7 3867 -3.868600e+02 6.270800e+02 +9 3867 -1.276140e+03 6.249299e+02 +11 3867 -5.803000e+02 5.374800e+02 +14 3867 2.188200e+02 3.731300e+02 +16 3867 -1.488000e+01 5.470200e+02 +4 3868 1.105300e+03 2.390100e+02 +7 3868 4.138300e+02 2.356200e+02 +4 3869 1.074020e+03 2.433000e+02 +5 3869 7.096899e+02 6.259600e+02 +6 3869 -1.210500e+02 -1.457100e+02 +8 3869 -1.986000e+02 -1.748999e+01 +4 3870 1.293680e+03 2.453900e+02 +8 3870 2.837700e+02 -6.367999e+01 +16 3870 7.075300e+02 2.746700e+02 +4 3871 8.754800e+02 2.464900e+02 +5 3871 4.470699e+02 5.995200e+02 +4 3872 -2.178700e+02 2.472300e+02 +5 3872 -1.022110e+03 3.794000e+02 +14 3872 -2.834600e+02 2.018100e+02 +15 3872 4.962400e+02 1.001500e+02 +16 3872 -6.934100e+02 2.520000e+02 +4 3873 8.951101e+02 2.526599e+02 +5 3873 4.702400e+02 6.108000e+02 +4 3874 8.786101e+02 2.585100e+02 +5 3874 4.490500e+02 6.160601e+02 +4 3875 1.135040e+03 2.603401e+02 +8 3875 -5.290997e+01 9.460022e+00 +16 3875 6.095800e+02 2.878700e+02 +4 3876 8.136699e+02 2.604500e+02 +5 3876 3.637300e+02 6.061600e+02 +4 3877 1.259570e+03 2.620801e+02 +8 3877 2.162700e+02 -1.864001e+01 +4 3878 1.018290e+03 2.727600e+02 +6 3878 -2.264300e+02 -5.756000e+01 +4 3879 8.279199e+02 2.846799e+02 +5 3879 3.772000e+02 6.411100e+02 +4 3880 8.740002e+01 2.864099e+02 +7 3880 -7.883500e+02 3.115000e+02 +14 3880 -2.119000e+01 2.233200e+02 +15 3880 8.458000e+02 1.432500e+02 +16 3880 -3.641200e+02 3.013700e+02 +19 3880 6.456899e+02 2.021500e+02 +4 3881 8.417004e+01 2.938401e+02 +7 3881 -7.901800e+02 3.205801e+02 +14 3881 -2.251001e+01 2.287800e+02 +15 3881 8.435800e+02 1.505000e+02 +16 3881 -3.664900e+02 3.093000e+02 +19 3881 6.421201e+02 2.150801e+02 +4 3882 9.206299e+02 3.162100e+02 +5 3882 4.935000e+02 6.988000e+02 +4 3883 9.332000e+02 3.304099e+02 +5 3883 5.077900e+02 7.186200e+02 +4 3884 8.240300e+02 3.739900e+02 +5 3884 3.542300e+02 7.593800e+02 +4 3885 3.860500e+02 4.228800e+02 +7 3885 -5.221700e+02 4.916899e+02 +9 3885 -1.464370e+03 4.428201e+02 +10 3885 -9.974700e+02 -2.365900e+02 +11 3885 -7.566700e+02 3.656200e+02 +16 3885 -1.170100e+02 4.412000e+02 +19 3885 1.121440e+03 3.978101e+02 +20 3885 -1.018160e+03 -4.872998e+01 +4 3886 3.708700e+02 4.367300e+02 +7 3886 -5.226200e+02 5.167800e+02 +4 3887 3.708700e+02 4.367300e+02 +7 3887 -5.517300e+02 5.119099e+02 +19 3887 1.088560e+03 4.175601e+02 +4 3888 7.226001e+01 4.378800e+02 +7 3888 -8.094700e+02 5.332000e+02 +10 3888 -1.211170e+03 -1.891500e+02 +15 3888 8.297600e+02 3.158101e+02 +20 3888 -1.137770e+03 -4.172998e+01 +4 3889 3.404900e+02 4.480901e+02 +7 3889 -6.131800e+02 5.299399e+02 +14 3889 8.978998e+01 3.130400e+02 +16 3889 -1.743100e+02 4.664299e+02 +19 3889 1.021970e+03 4.264800e+02 +4 3890 3.404900e+02 4.480901e+02 +7 3890 -6.131800e+02 5.299399e+02 +14 3890 8.978998e+01 3.130400e+02 +16 3890 -1.743100e+02 4.664299e+02 +19 3890 1.021970e+03 4.264800e+02 +4 3891 4.631400e+02 4.761200e+02 +7 3891 -3.954800e+02 5.619000e+02 +9 3891 -1.259420e+03 5.288800e+02 +10 3891 -8.656500e+02 -1.759301e+02 +11 3891 -5.633900e+02 4.468500e+02 +14 3891 2.103600e+02 3.392400e+02 +16 3891 -3.132001e+01 4.948101e+02 +18 3891 -1.052980e+03 2.267400e+02 +20 3891 -9.034200e+02 -4.090027e+00 +4 3892 4.018300e+02 4.865000e+02 +7 3892 -4.976900e+02 5.776200e+02 +9 3892 -1.425730e+03 5.549500e+02 +10 3892 -9.682500e+02 -1.597900e+02 +11 3892 -7.211600e+02 4.708800e+02 +16 3892 -1.010300e+02 5.044500e+02 +19 3892 1.150980e+03 5.089900e+02 +20 3892 -9.932400e+02 1.263000e+01 +4 3893 3.863800e+02 4.887200e+02 +7 3893 -5.244300e+02 5.835400e+02 +16 3893 -1.187800e+02 5.081400e+02 +19 3893 1.119590e+03 5.118301e+02 +4 3894 4.593199e+02 5.027300e+02 +7 3894 -4.175300e+02 5.970601e+02 +9 3894 -1.310630e+03 5.814700e+02 +10 3894 -8.915400e+02 -1.436400e+02 +11 3894 -6.139000e+02 4.965800e+02 +14 3894 1.971600e+02 3.557000e+02 +16 3894 -4.315002e+01 5.220300e+02 +18 3894 -1.083300e+03 2.604600e+02 +19 3894 1.256830e+03 5.452300e+02 +4 3895 1.219800e+02 5.321000e+02 +7 3895 -7.567200e+02 6.672900e+02 +10 3895 -1.158650e+03 -6.654004e+01 +16 3895 -3.409500e+02 5.625100e+02 +4 3896 1.152500e+02 5.356200e+02 +7 3896 -7.646100e+02 6.740100e+02 +16 3896 -3.477000e+02 5.670100e+02 +4 3897 3.771997e+01 5.361700e+02 +7 3897 -8.555500e+02 6.818700e+02 +10 3897 -1.243200e+03 -4.856995e+01 +14 3897 -5.234000e+01 4.414600e+02 +16 3897 -4.232200e+02 5.699500e+02 +4 3898 1.043700e+02 5.791500e+02 +7 3898 -7.773600e+02 7.398500e+02 +10 3898 -1.171390e+03 1.709961e+00 +14 3898 -4.109985e+00 4.693300e+02 +15 3898 8.630900e+02 4.764800e+02 +4 3899 5.915002e+01 2.554900e+02 +7 3899 -8.557800e+02 2.640200e+02 +4 3900 5.915002e+01 2.554900e+02 +7 3900 -8.557800e+02 2.640200e+02 +4 3901 9.362200e+02 2.767500e+02 +5 3901 5.215200e+02 6.489600e+02 +4 3902 1.094210e+03 2.794500e+02 +5 3902 7.298101e+02 6.749700e+02 +6 3902 -8.609998e+01 -7.970001e+01 +8 3902 -1.504100e+02 6.959998e+01 +4 3903 2.406995e+01 2.952800e+02 +7 3903 -8.655200e+02 3.246899e+02 +14 3903 -6.807999e+01 2.345200e+02 +15 3903 7.758700e+02 1.529000e+02 +16 3903 -4.274600e+02 3.102300e+02 +19 3903 5.299100e+02 2.218000e+02 +4 3904 -1.698600e+02 2.999399e+02 +5 3904 -9.696800e+02 4.629299e+02 +4 3905 1.107240e+03 3.167100e+02 +5 3905 7.393800e+02 7.250800e+02 +8 3905 -1.203500e+02 1.625700e+02 +4 3906 9.069900e+02 3.336500e+02 +5 3906 4.714500e+02 7.192400e+02 +4 3907 9.069900e+02 3.449500e+02 +5 3907 4.693400e+02 7.345200e+02 +4 3908 1.061600e+03 3.844399e+02 +5 3908 6.669800e+02 8.059100e+02 +6 3908 -1.375400e+02 1.615600e+02 +4 3909 8.934800e+02 4.032400e+02 +5 3909 4.392200e+02 8.081899e+02 +8 3909 -7.020400e+02 4.775800e+02 +4 3910 9.258701e+02 4.189399e+02 +5 3910 4.795699e+02 8.333300e+02 +4 3911 7.280005e+01 4.237200e+02 +7 3911 -8.088700e+02 5.127600e+02 +14 3911 -2.901999e+01 3.415300e+02 +15 3911 8.297300e+02 2.997600e+02 +4 3912 3.315500e+02 4.286500e+02 +7 3912 -6.265700e+02 5.025500e+02 +16 3912 -1.841700e+02 4.456600e+02 +19 3912 1.006980e+03 3.915400e+02 +4 3913 4.409000e+02 4.428600e+02 +7 3913 -4.209200e+02 5.163800e+02 +9 3913 -1.292690e+03 4.661699e+02 +11 3913 -5.927400e+02 3.875701e+02 +14 3913 1.950700e+02 3.155400e+02 +16 3913 -5.169000e+01 4.622500e+02 +19 3913 1.242160e+03 4.490400e+02 +4 3914 8.183701e+02 4.566200e+02 +5 3914 3.298500e+02 8.680500e+02 +7 3914 1.677400e+02 5.147600e+02 +8 3914 -9.225100e+02 6.568000e+02 +9 3914 -4.127600e+02 4.339800e+02 +11 3914 2.439200e+02 3.627400e+02 +12 3914 -9.353100e+02 -3.252100e+02 +4 3915 1.373000e+02 4.580200e+02 +7 3915 -7.398500e+02 5.594000e+02 +14 3915 1.404001e+01 3.615700e+02 +15 3915 8.975500e+02 3.390900e+02 +16 3915 -3.245300e+02 4.845000e+02 +19 3915 7.303799e+02 5.149600e+02 +4 3916 4.313101e+02 4.677800e+02 +7 3916 -4.518400e+02 5.512500e+02 +9 3916 -1.355370e+03 5.188900e+02 +10 3916 -9.246500e+02 -1.841100e+02 +11 3916 -6.541800e+02 4.372800e+02 +16 3916 -6.881000e+01 4.867700e+02 +18 3916 -1.112610e+03 2.224700e+02 +19 3916 1.210130e+03 4.833700e+02 +4 3917 4.261801e+02 4.730901e+02 +7 3917 -4.594100e+02 5.617900e+02 +9 3917 -1.369540e+03 5.330801e+02 +10 3917 -9.319500e+02 -1.730300e+02 +11 3917 -6.612900e+02 4.454500e+02 +14 3917 1.734500e+02 3.369100e+02 +16 3917 -7.428998e+01 4.944000e+02 +18 3917 -1.120080e+03 2.310200e+02 +19 3917 1.200170e+03 4.944299e+02 +20 3917 -9.624400e+02 -1.599731e-01 +4 3918 4.323300e+02 4.762000e+02 +7 3918 -4.462700e+02 5.674700e+02 +9 3918 -1.347770e+03 5.406200e+02 +10 3918 -9.187700e+02 -1.694399e+02 +11 3918 -6.483900e+02 4.578800e+02 +14 3918 1.804900e+02 3.399700e+02 +16 3918 -6.921997e+01 4.951899e+02 +19 3918 1.218030e+03 5.041500e+02 +20 3918 -9.548200e+02 -1.309998e+00 +4 3919 8.264900e+02 4.955701e+02 +5 3919 3.301899e+02 9.214500e+02 +4 3920 9.092004e+01 5.411700e+02 +7 3920 -7.897500e+02 6.840200e+02 +14 3920 -1.295999e+01 4.394100e+02 +4 3921 1.275300e+02 5.551700e+02 +7 3921 -7.493700e+02 7.010000e+02 +15 3921 8.874500e+02 4.489800e+02 +16 3921 -3.355400e+02 5.875300e+02 +4 3922 7.793994e+01 5.651400e+02 +7 3922 -8.036900e+02 7.200000e+02 +15 3922 8.362000e+02 4.600701e+02 +16 3922 -3.827500e+02 5.997100e+02 +4 3923 7.032996e+01 5.794100e+02 +7 3923 -8.152000e+02 7.422600e+02 +10 3923 -1.203380e+03 5.319946e+00 +14 3923 -2.732999e+01 4.739600e+02 +15 3923 8.269100e+02 4.762400e+02 +16 3923 -3.914100e+02 6.154900e+02 +19 3923 6.113900e+02 7.513101e+02 +4 3924 -1.932500e+02 1.999399e+02 +5 3924 -9.762600e+02 3.201300e+02 +4 3925 5.262000e+01 2.007800e+02 +7 3925 -8.294000e+02 1.831500e+02 +15 3925 8.062500e+02 4.385999e+01 +16 3925 -3.950000e+02 2.088800e+02 +4 3926 -1.638400e+02 2.082500e+02 +5 3926 -9.388600e+02 3.382400e+02 +4 3927 4.020996e+01 2.156200e+02 +7 3927 -8.457000e+02 2.049800e+02 +14 3927 -5.835999e+01 1.635700e+02 +4 3928 -5.631006e+01 2.156300e+02 +7 3928 -9.731800e+02 2.051200e+02 +4 3929 -2.338500e+02 2.259900e+02 +5 3929 -1.037190e+03 3.468700e+02 +4 3930 1.132640e+03 2.343101e+02 +8 3930 -5.528998e+01 -5.525000e+01 +4 3931 9.169700e+02 2.394500e+02 +5 3931 5.031100e+02 5.969900e+02 +4 3932 -6.672998e+01 2.417500e+02 +7 3932 -9.941400e+02 2.449199e+02 +14 3932 -1.455100e+02 1.915100e+02 +15 3932 6.717400e+02 9.192999e+01 +16 3932 -5.211300e+02 2.502400e+02 +4 3933 -2.380699e+02 2.444700e+02 +5 3933 -1.047270e+03 3.717800e+02 +4 3934 1.289190e+03 2.511899e+02 +8 3934 2.745200e+02 -4.904999e+01 +4 3935 1.008430e+03 2.560901e+02 +5 3935 6.213400e+02 6.329600e+02 +7 3935 3.444000e+02 2.558600e+02 +4 3936 9.190701e+02 2.577100e+02 +5 3936 5.025800e+02 6.217700e+02 +4 3937 8.078301e+02 2.620901e+02 +7 3937 1.576400e+02 2.663600e+02 +11 3937 2.337900e+02 5.990002e+01 +18 3937 -5.377400e+02 -4.231995e+01 +4 3938 1.207030e+03 2.787700e+02 +8 3938 1.074399e+02 3.572998e+01 +4 3939 1.009810e+03 2.842500e+02 +5 3939 6.174500e+02 6.701000e+02 +4 3940 8.844099e+02 3.048600e+02 +5 3940 4.466700e+02 6.777400e+02 +4 3941 9.081001e+02 3.060601e+02 +5 3941 4.790300e+02 6.832600e+02 +4 3942 1.260970e+03 3.097000e+02 +8 3942 2.157000e+02 8.925000e+01 +4 3943 7.798999e+02 3.119600e+02 +5 3943 3.092900e+02 6.687300e+02 +4 3944 -1.148999e+01 3.212600e+02 +7 3944 -9.166600e+02 3.643301e+02 +15 3944 7.358500e+02 1.830700e+02 +16 3944 -4.666900e+02 3.382500e+02 +4 3945 9.674900e+02 3.261500e+02 +5 3945 5.534500e+02 7.177200e+02 +4 3946 -3.909998e+01 3.286400e+02 +7 3946 -9.577300e+02 3.762100e+02 +15 3946 7.039399e+02 1.914900e+02 +16 3946 -4.952100e+02 3.454800e+02 +4 3947 9.503601e+02 3.429299e+02 +5 3947 5.278500e+02 7.377000e+02 +4 3948 1.164420e+03 3.495500e+02 +5 3948 8.079299e+02 7.726400e+02 +6 3948 2.756995e+01 2.603003e+01 +8 3948 1.015002e+01 2.202800e+02 +4 3949 -2.321997e+01 3.702800e+02 +7 3949 -9.339900e+02 4.382900e+02 +14 3949 -1.050800e+02 3.030400e+02 +15 3949 7.241100e+02 2.387900e+02 +4 3950 1.080440e+03 3.791000e+02 +8 3950 -1.897000e+02 3.349800e+02 +4 3951 5.454004e+01 3.803500e+02 +7 3951 -8.300400e+02 4.495701e+02 +10 3951 -1.234040e+03 -2.679301e+02 +14 3951 -4.331000e+01 3.059600e+02 +15 3951 8.104200e+02 2.502000e+02 +18 3951 -1.340940e+03 1.130801e+02 +19 3951 5.850400e+02 3.818301e+02 +20 3951 -1.152990e+03 -1.031600e+02 +4 3952 9.459800e+02 3.943201e+02 +5 3952 5.119700e+02 8.049100e+02 +4 3953 1.084220e+03 3.967000e+02 +8 3953 -1.814400e+02 3.762700e+02 +4 3954 8.198999e+01 4.190000e+02 +7 3954 -7.965800e+02 5.054399e+02 +19 3954 6.352700e+02 4.524700e+02 +4 3955 4.196000e+02 4.306100e+02 +7 3955 -4.640300e+02 5.002100e+02 +9 3955 -1.370630e+03 4.472300e+02 +11 3955 -6.679200e+02 3.694299e+02 +18 3955 -1.124220e+03 1.773700e+02 +20 3955 -9.660500e+02 -4.675000e+01 +4 3956 4.492900e+02 4.309299e+02 +7 3956 -4.060700e+02 4.993301e+02 +16 3956 -4.044000e+01 4.508600e+02 +19 3956 1.260710e+03 4.288900e+02 +4 3957 8.216003e+01 4.364500e+02 +7 3957 -8.799400e+02 5.419800e+02 +4 3958 3.494301e+02 4.411599e+02 +7 3958 -5.934600e+02 5.173800e+02 +10 3958 -1.071370e+03 -2.118800e+02 +14 3958 9.956000e+01 3.089800e+02 +16 3958 -1.628300e+02 4.579800e+02 +19 3958 1.041110e+03 4.151300e+02 +20 3958 -1.083240e+03 -2.504999e+01 +4 3959 3.494301e+02 4.411599e+02 +7 3959 -5.934600e+02 5.173800e+02 +10 3959 -1.071370e+03 -2.118800e+02 +14 3959 9.956000e+01 3.089800e+02 +16 3959 -1.628300e+02 4.579800e+02 +19 3959 1.041110e+03 4.151300e+02 +4 3960 4.011400e+02 4.477100e+02 +7 3960 -4.960000e+02 5.252200e+02 +9 3960 -1.419740e+03 4.840200e+02 +10 3960 -9.684600e+02 -2.070699e+02 +11 3960 -7.150700e+02 4.051000e+02 +16 3960 -1.001000e+02 4.657200e+02 +19 3960 1.152250e+03 4.447300e+02 +20 3960 -9.918200e+02 -2.602002e+01 +4 3961 3.852100e+02 4.516200e+02 +7 3961 -5.260800e+02 5.309800e+02 +9 3961 -1.470850e+03 4.938900e+02 +10 3961 -9.994000e+02 -2.010601e+02 +11 3961 -7.627700e+02 4.145400e+02 +16 3961 -1.201800e+02 4.698500e+02 +18 3961 -1.185690e+03 2.083800e+02 +19 3961 1.117760e+03 4.462300e+02 +20 3961 -1.019420e+03 -1.995001e+01 +4 3962 4.079100e+02 4.580801e+02 +7 3962 -4.852800e+02 5.385300e+02 +9 3962 -1.398520e+03 5.018201e+02 +10 3962 -9.568200e+02 -1.950699e+02 +14 3962 1.603900e+02 3.252900e+02 +16 3962 -9.356000e+01 4.767600e+02 +19 3962 1.165370e+03 4.639000e+02 +20 3962 -9.793300e+02 -1.671997e+01 +4 3963 3.961200e+02 4.588101e+02 +7 3963 -5.049600e+02 5.412600e+02 +10 3963 -9.777000e+02 -1.918800e+02 +14 3963 1.483300e+02 3.253900e+02 +16 3963 -1.058800e+02 4.782400e+02 +19 3963 1.141950e+03 4.624900e+02 +4 3964 6.939001e+01 4.708700e+02 +7 3964 -8.148300e+02 5.824399e+02 +14 3964 -3.057001e+01 3.819800e+02 +4 3965 1.659998e+01 4.707600e+02 +7 3965 -8.806900e+02 5.880500e+02 +14 3965 -6.939001e+01 3.881700e+02 +19 3965 5.135601e+02 5.563600e+02 +4 3966 8.426001e+02 4.775300e+02 +5 3966 3.570300e+02 9.001801e+02 +4 3967 3.952000e+02 4.816799e+02 +7 3967 -5.069200e+02 5.719100e+02 +9 3967 -1.439770e+03 5.486000e+02 +11 3967 -7.346300e+02 4.649700e+02 +14 3967 1.471300e+02 3.419900e+02 +16 3967 -1.078800e+02 5.009399e+02 +19 3967 1.138930e+03 5.017800e+02 +20 3967 -1.001440e+03 8.830017e+00 +4 3968 8.012300e+02 4.868401e+02 +7 3968 1.473900e+02 5.543401e+02 +4 3969 9.375000e+01 4.945400e+02 +7 3969 -7.842400e+02 6.142700e+02 +10 3969 -1.182860e+03 -1.164800e+02 +15 3969 8.533900e+02 3.790200e+02 +19 3969 6.534900e+02 5.918600e+02 +4 3970 4.401100e+02 5.039800e+02 +7 3970 -4.409100e+02 5.999200e+02 +10 3970 -9.123200e+02 -1.399200e+02 +11 3970 -6.423800e+02 5.009399e+02 +19 3970 1.225700e+03 5.467900e+02 +4 3971 4.984600e+02 5.203300e+02 +7 3971 -3.673199e+02 6.187100e+02 +10 3971 -8.445700e+02 -1.254000e+02 +11 3971 -5.524600e+02 5.252300e+02 +16 3971 -5.349976e+00 5.397500e+02 +18 3971 -1.040150e+03 2.779299e+02 +4 3972 4.950300e+02 5.234200e+02 +7 3972 -3.735400e+02 6.222000e+02 +9 3972 -1.253850e+03 6.166300e+02 +11 3972 -5.613600e+02 5.293400e+02 +14 3972 2.221800e+02 3.689300e+02 +16 3972 -9.190002e+00 5.420800e+02 +18 3972 -1.045500e+03 2.812000e+02 +19 3972 1.321800e+03 5.816300e+02 +20 3972 -8.969400e+02 4.216992e+01 +4 3973 4.930200e+02 5.350400e+02 +7 3973 -3.759399e+02 6.382700e+02 +9 3973 -1.258770e+03 6.392700e+02 +11 3973 -5.664600e+02 5.514100e+02 +19 3973 1.319290e+03 6.006100e+02 +4 3974 8.551001e+01 5.398500e+02 +5 3974 -6.627700e+02 8.427800e+02 +4 3975 5.551001e+01 5.625200e+02 +7 3975 -8.323000e+02 7.192300e+02 +10 3975 -1.218850e+03 -1.554004e+01 +14 3975 -3.798999e+01 4.623600e+02 +15 3975 8.112300e+02 4.571600e+02 +16 3975 -4.050100e+02 5.973600e+02 +19 3975 5.844600e+02 7.227400e+02 +4 3976 1.410601e+02 5.702300e+02 +7 3976 -7.421900e+02 7.221300e+02 +15 3976 8.991400e+02 4.657800e+02 +16 3976 -3.262800e+02 6.021500e+02 +4 3977 1.168994e+01 5.719200e+02 +7 3977 -8.886200e+02 7.382600e+02 +10 3977 -1.267960e+03 4.949951e+00 +14 3977 -7.117001e+01 4.769399e+02 +15 3977 7.634600e+02 4.677000e+02 +16 3977 -4.502200e+02 6.093300e+02 +19 3977 5.036899e+02 7.444600e+02 +4 3978 2.300049e+00 5.722100e+02 +7 3978 -9.020600e+02 7.401500e+02 +14 3978 -7.848001e+01 4.781600e+02 +15 3978 7.523101e+02 4.678700e+02 +19 3978 4.852000e+02 7.459500e+02 +4 3979 4.546997e+01 2.004199e+02 +7 3979 -8.397100e+02 1.820801e+02 +4 3980 -2.231006e+01 2.265200e+02 +7 3980 -9.282800e+02 2.216699e+02 +14 3980 -1.072800e+02 1.763500e+02 +15 3980 7.231600e+02 7.448999e+01 +16 3980 -4.717700e+02 2.347000e+02 +4 3981 1.163780e+03 2.416300e+02 +5 3981 8.267400e+02 6.353201e+02 +8 3981 1.546997e+01 -4.459003e+01 +4 3982 -8.878003e+01 2.416300e+02 +7 3982 -1.026780e+03 2.455200e+02 +14 3982 -1.647800e+02 1.926600e+02 +15 3982 6.472500e+02 9.228003e+01 +16 3982 -5.453400e+02 2.498000e+02 +4 3983 1.121550e+03 2.436100e+02 +8 3983 -8.081000e+01 -2.858002e+01 +4 3984 1.009050e+03 2.467500e+02 +5 3984 6.242400e+02 6.205900e+02 +4 3985 9.223799e+02 2.599600e+02 +5 3985 5.067000e+02 6.242200e+02 +4 3986 9.028000e+02 2.608401e+02 +5 3986 4.804500e+02 6.224600e+02 +4 3987 8.726699e+02 2.610801e+02 +5 3987 4.406801e+02 6.179399e+02 +4 3988 9.756399e+02 2.684199e+02 +5 3988 5.750100e+02 6.438700e+02 +4 3989 1.085190e+03 2.731799e+02 +5 3989 7.198500e+02 6.660701e+02 +8 3989 -1.715600e+02 5.477002e+01 +4 3990 1.028600e+02 2.905601e+02 +7 3990 -7.731900e+02 3.152200e+02 +4 3991 7.893005e+01 2.949000e+02 +7 3991 -7.980700e+02 3.217700e+02 +14 3991 -2.735999e+01 2.302900e+02 +15 3991 8.357800e+02 1.522900e+02 +16 3991 -3.724500e+02 3.100701e+02 +4 3992 9.160300e+02 3.062900e+02 +5 3992 4.894399e+02 6.846300e+02 +4 3993 1.002150e+03 3.200100e+02 +5 3993 6.012100e+02 7.150200e+02 +4 3994 4.787000e+01 3.199000e+02 +7 3994 -8.378500e+02 3.602400e+02 +10 3994 -1.247270e+03 -3.538199e+02 +15 3994 8.021000e+02 1.810300e+02 +16 3994 -4.052200e+02 3.368300e+02 +19 3994 5.731100e+02 2.672100e+02 +4 3995 -3.295996e+01 3.214399e+02 +7 3995 -9.475700e+02 3.654700e+02 +15 3995 7.109000e+02 1.832300e+02 +16 3995 -4.887200e+02 3.379100e+02 +4 3996 8.266699e+02 3.239700e+02 +5 3996 3.675601e+02 6.941400e+02 +4 3997 8.152900e+02 3.236500e+02 +5 3997 3.529000e+02 6.910900e+02 +4 3998 -9.525000e+01 3.258500e+02 +7 3998 -1.039330e+03 3.744600e+02 +15 3998 6.414700e+02 1.881600e+02 +19 3998 3.047600e+02 2.820500e+02 +4 3999 -1.400699e+02 3.320200e+02 +5 3999 -9.375200e+02 5.134600e+02 +14 3999 -2.079800e+02 2.759700e+02 +15 3999 5.894800e+02 1.957600e+02 +16 3999 -6.048400e+02 3.481400e+02 +19 3999 2.194100e+02 2.938301e+02 +4 4000 9.323301e+02 3.391300e+02 +5 4000 5.043600e+02 7.326100e+02 +4 4001 9.416001e+02 3.554000e+02 +5 4001 5.134200e+02 7.534800e+02 +4 4002 9.982996e+01 3.577900e+02 +7 4002 -7.769600e+02 4.138201e+02 +14 4002 -1.223999e+01 2.819300e+02 +15 4002 8.582900e+02 2.238800e+02 +16 4002 -3.555300e+02 3.777300e+02 +19 4002 6.677900e+02 3.338401e+02 +4 4003 6.905005e+01 3.601500e+02 +7 4003 -8.978200e+02 4.262800e+02 +4 4004 9.037600e+02 3.607600e+02 +5 4004 4.602800e+02 7.546100e+02 +4 4005 9.087300e+02 3.629700e+02 +5 4005 4.673600e+02 7.584100e+02 +4 4006 9.087300e+02 3.629700e+02 +5 4006 4.673600e+02 7.584100e+02 +4 4007 -4.037000e+01 3.706100e+02 +7 4007 -9.586400e+02 4.398500e+02 +15 4007 7.031500e+02 2.392700e+02 +16 4007 -4.980700e+02 3.913700e+02 +4 4008 -1.065200e+02 3.708301e+02 +7 4008 -9.412600e+02 4.386400e+02 +4 4009 -1.526100e+02 3.708401e+02 +5 4009 -9.630900e+02 5.649000e+02 +4 4010 9.094299e+02 3.892700e+02 +8 4010 -6.543500e+02 4.373300e+02 +4 4011 8.615300e+02 3.917000e+02 +5 4011 3.989000e+02 7.895800e+02 +4 4012 1.174520e+03 4.126599e+02 +6 4012 2.919995e+01 1.221200e+02 +8 4012 2.708997e+01 3.546400e+02 +16 4012 6.195300e+02 4.296100e+02 +4 4013 5.116003e+01 4.448401e+02 +7 4013 -8.362300e+02 5.456100e+02 +10 4013 -1.234200e+03 -1.769200e+02 +14 4013 -4.425000e+01 3.617900e+02 +15 4013 8.065200e+02 3.233700e+02 +16 4013 -4.055000e+02 4.713600e+02 +19 4013 5.782800e+02 5.027600e+02 +4 4014 3.643600e+02 4.490601e+02 +7 4014 -5.635800e+02 5.295901e+02 +10 4014 -1.039820e+03 -2.011100e+02 +11 4014 -8.271600e+02 4.162600e+02 +14 4014 1.159800e+02 3.168000e+02 +16 4014 -1.444200e+02 4.670300e+02 +19 4014 1.075800e+03 4.368201e+02 +20 4014 -1.055640e+03 -1.791998e+01 +4 4015 1.606995e+01 4.510500e+02 +7 4015 -8.808300e+02 5.574500e+02 +10 4015 -1.273000e+03 -1.638700e+02 +15 4015 7.682600e+02 3.312800e+02 +18 4015 -1.376960e+03 2.048101e+02 +4 4016 3.973700e+02 4.553101e+02 +7 4016 -5.011400e+02 5.360200e+02 +10 4016 -9.741900e+02 -1.971100e+02 +11 4016 -7.230100e+02 4.191500e+02 +14 4016 1.498600e+02 3.228800e+02 +16 4016 -1.049000e+02 4.739100e+02 +18 4016 -1.158760e+03 2.107600e+02 +4 4017 -6.943005e+01 4.563000e+02 +7 4017 -1.003390e+03 5.722000e+02 +10 4017 -1.388550e+03 -1.456801e+02 +15 4017 6.714301e+02 3.367000e+02 +16 4017 -5.330100e+02 4.848800e+02 +4 4018 7.848201e+02 4.607100e+02 +5 4018 2.853900e+02 8.677200e+02 +4 4019 7.509998e+01 4.747500e+02 +7 4019 -8.897500e+02 5.994399e+02 +4 4020 3.820601e+02 4.779600e+02 +7 4020 -5.313600e+02 5.673300e+02 +9 4020 -1.481500e+03 5.439099e+02 +10 4020 -1.004320e+03 -1.678900e+02 +11 4020 -7.750900e+02 4.620300e+02 +14 4020 1.337000e+02 3.384100e+02 +16 4020 -1.236700e+02 4.964900e+02 +19 4020 1.110690e+03 4.908600e+02 +20 4020 -1.024180e+03 7.049988e+00 +4 4021 4.616300e+02 4.814199e+02 +7 4021 -3.965800e+02 5.679500e+02 +10 4021 -8.665000e+02 -1.714200e+02 +11 4021 -5.655300e+02 4.529200e+02 +14 4021 2.095800e+02 3.439200e+02 +16 4021 -3.289001e+01 5.017200e+02 +18 4021 -1.053880e+03 2.322500e+02 +20 4021 -9.045300e+02 -1.699829e-01 +4 4022 7.785200e+02 4.888900e+02 +5 4022 2.731899e+02 9.032600e+02 +4 4023 8.041699e+02 4.985300e+02 +5 4023 3.025601e+02 9.217200e+02 +4 4024 4.264800e+02 5.245100e+02 +7 4024 -4.635500e+02 6.297000e+02 +9 4024 -1.380930e+03 6.270000e+02 +10 4024 -9.343700e+02 -1.125400e+02 +11 4024 -6.803800e+02 5.407900e+02 +14 4024 1.714500e+02 3.728200e+02 +16 4024 -7.666998e+01 5.448000e+02 +19 4024 1.196160e+03 5.792800e+02 +20 4024 -9.661700e+02 5.034009e+01 +4 4025 1.595996e+01 2.292800e+02 +7 4025 -8.754400e+02 2.255801e+02 +10 4025 -1.289630e+03 -4.842500e+02 +15 4025 7.664500e+02 7.677002e+01 +16 4025 -4.327000e+02 2.386700e+02 +18 4025 -1.379670e+03 -7.769995e+01 +20 4025 -1.190540e+03 -2.695100e+02 +4 4026 -2.009998e+01 2.296799e+02 +7 4026 -9.249300e+02 2.261300e+02 +15 4026 7.256500e+02 7.772998e+01 +16 4026 -4.712300e+02 2.384100e+02 +20 4026 -1.224880e+03 -2.693199e+02 +4 4027 -9.988000e+01 2.337100e+02 +7 4027 -1.043550e+03 2.327500e+02 +14 4027 -1.747100e+02 1.857800e+02 +4 4028 -2.102000e+02 2.544199e+02 +5 4028 -1.014370e+03 3.892300e+02 +19 4028 8.573999e+01 1.433401e+02 +4 4029 -5.988000e+01 2.615400e+02 +7 4029 -9.836600e+02 2.749700e+02 +14 4029 -1.387700e+02 2.090600e+02 +15 4029 6.803300e+02 1.146000e+02 +4 4030 -5.988000e+01 2.615400e+02 +7 4030 -9.836600e+02 2.749700e+02 +14 4030 -1.387700e+02 2.090600e+02 +4 4031 9.695901e+02 2.696300e+02 +5 4031 5.663000e+02 6.451500e+02 +4 4032 8.388401e+02 2.746699e+02 +5 4032 3.938700e+02 6.306799e+02 +4 4033 9.312000e+02 2.816400e+02 +5 4033 5.146200e+02 6.541300e+02 +4 4034 9.612000e+02 2.824900e+02 +5 4034 5.539000e+02 6.604200e+02 +4 4035 7.795996e+01 3.034399e+02 +7 4035 -7.987000e+02 3.344399e+02 +15 4035 8.360400e+02 1.616900e+02 +4 4036 7.795996e+01 3.034399e+02 +7 4036 -8.825600e+02 3.392700e+02 +4 4037 1.137600e+02 3.061500e+02 +7 4037 -7.588600e+02 3.373600e+02 +15 4037 8.750900e+02 1.640300e+02 +4 4038 7.295996e+01 3.083600e+02 +7 4038 -8.052900e+02 3.420300e+02 +10 4038 -1.218110e+03 -3.719500e+02 +15 4038 8.297400e+02 1.675900e+02 +19 4038 6.201700e+02 2.435400e+02 +4 4039 9.313999e+02 3.108201e+02 +5 4039 5.093800e+02 6.934399e+02 +4 4040 6.151001e+01 3.136100e+02 +7 4040 -8.210000e+02 3.499900e+02 +4 4041 1.082210e+03 3.176100e+02 +5 4041 7.067600e+02 7.219900e+02 +8 4041 -1.816400e+02 1.703100e+02 +4 4042 9.702300e+02 3.240400e+02 +5 4042 5.581200e+02 7.152500e+02 +4 4043 9.320100e+02 3.252100e+02 +5 4043 5.070300e+02 7.103600e+02 +4 4044 9.969900e+02 3.273101e+02 +5 4044 5.920699e+02 7.239200e+02 +4 4045 9.521799e+02 3.326100e+02 +5 4045 5.316000e+02 7.245100e+02 +4 4046 1.240800e+02 3.374700e+02 +7 4046 -7.500400e+02 3.809299e+02 +19 4046 7.105100e+02 2.907800e+02 +4 4047 1.642004e+01 3.461200e+02 +7 4047 -8.790100e+02 4.012000e+02 +10 4047 -1.281850e+03 -3.132300e+02 +15 4047 7.673300e+02 2.115400e+02 +4 4048 2.405005e+01 3.690901e+02 +7 4048 -8.688300e+02 4.342200e+02 +15 4048 7.772000e+02 2.373400e+02 +19 4048 5.295200e+02 3.622100e+02 +4 4049 -5.138000e+01 3.710801e+02 +7 4049 -9.731400e+02 4.411000e+02 +15 4049 6.915800e+02 2.398700e+02 +4 4050 9.619099e+02 3.789199e+02 +5 4050 5.366000e+02 7.867600e+02 +4 4051 -1.330005e+01 3.801300e+02 +7 4051 -9.206500e+02 4.525901e+02 +15 4051 7.343101e+02 2.501200e+02 +18 4051 -1.410620e+03 1.147200e+02 +19 4051 4.583800e+02 3.844099e+02 +20 4051 -1.213670e+03 -1.018400e+02 +4 4052 8.393899e+02 3.872500e+02 +5 4052 3.703000e+02 7.801400e+02 +4 4053 8.424900e+02 3.891699e+02 +5 4053 3.740200e+02 7.832300e+02 +4 4054 -1.010900e+02 3.906100e+02 +7 4054 -1.050160e+03 4.737200e+02 +15 4054 6.343900e+02 2.617200e+02 +19 4054 2.925200e+02 4.047500e+02 +4 4055 4.080900e+02 4.226000e+02 +7 4055 -4.799300e+02 4.899299e+02 +9 4055 -1.392490e+03 4.347600e+02 +11 4055 -6.865000e+02 3.574299e+02 +18 4055 -1.137040e+03 1.701500e+02 +4 4056 1.139500e+02 4.439099e+02 +7 4056 -7.835300e+02 5.440200e+02 +4 4057 3.810000e+02 4.446799e+02 +7 4057 -5.306900e+02 5.218401e+02 +11 4057 -7.719000e+02 4.034299e+02 +19 4057 1.111480e+03 4.334800e+02 +4 4058 9.989990e+00 4.478301e+02 +7 4058 -8.899900e+02 5.532600e+02 +10 4058 -1.282930e+03 -1.686500e+02 +14 4058 -7.616000e+01 3.685100e+02 +15 4058 7.607800e+02 3.270701e+02 +4 4059 3.703199e+02 4.620701e+02 +7 4059 -5.537900e+02 5.459500e+02 +9 4059 -1.520010e+03 5.152500e+02 +14 4059 1.215600e+02 3.259300e+02 +16 4059 -1.376600e+02 4.800500e+02 +19 4059 1.086100e+03 4.588800e+02 +20 4059 -1.045990e+03 -7.020020e+00 +4 4060 1.241500e+02 4.668900e+02 +7 4060 -7.525600e+02 5.713800e+02 +10 4060 -1.161070e+03 -1.556100e+02 +19 4060 7.085200e+02 5.332400e+02 +4 4061 1.175900e+02 4.776799e+02 +7 4061 -7.594200e+02 5.892200e+02 +10 4061 -1.164840e+03 -1.387400e+02 +16 4061 -3.423000e+02 5.053900e+02 +19 4061 6.959800e+02 5.575000e+02 +4 4062 4.540400e+02 4.869600e+02 +7 4062 -4.143400e+02 5.753600e+02 +9 4062 -1.295810e+03 5.492500e+02 +11 4062 -5.973200e+02 4.658900e+02 +18 4062 -1.074200e+03 2.397700e+02 +20 4062 -9.219100e+02 7.190002e+00 +4 4063 4.480699e+02 5.008500e+02 +7 4063 -4.310000e+02 5.955500e+02 +9 4063 -1.329220e+03 5.792800e+02 +10 4063 -9.042600e+02 -1.444900e+02 +11 4063 -6.308100e+02 4.946799e+02 +19 4063 1.239600e+03 5.415400e+02 +4 4064 4.478101e+02 5.036300e+02 +7 4064 -4.320600e+02 5.986600e+02 +9 4064 -1.330100e+03 5.842200e+02 +10 4064 -9.050000e+02 -1.414800e+02 +11 4064 -6.325900e+02 4.991000e+02 +18 4064 -1.095800e+03 2.621100e+02 +19 4064 1.237800e+03 5.453800e+02 +4 4065 1.240200e+02 5.207700e+02 +7 4065 -7.537100e+02 6.505300e+02 +15 4065 8.837500e+02 4.088500e+02 +4 4066 4.915000e+02 5.223800e+02 +7 4066 -3.784100e+02 6.218000e+02 +18 4066 -1.050590e+03 2.796500e+02 +4 4067 5.044399e+02 5.253800e+02 +7 4067 -3.597500e+02 6.243500e+02 +9 4067 -1.234590e+03 6.197300e+02 +11 4067 -5.430500e+02 5.324700e+02 +16 4067 -1.099976e+00 5.443300e+02 +4 4068 1.241500e+02 5.259800e+02 +7 4068 -7.536400e+02 6.579600e+02 +10 4068 -1.156400e+03 -7.432996e+01 +4 4069 1.159100e+02 5.755100e+02 +7 4069 -7.656400e+02 7.314700e+02 +10 4069 -1.162330e+03 -6.750000e+00 +19 4069 6.906299e+02 7.353101e+02 +5 4070 1.567600e+02 9.191000e+02 +7 4070 -5.943994e+01 6.025400e+02 +9 4070 -7.534400e+02 5.728101e+02 +11 4070 -8.478998e+01 4.925300e+02 +14 4070 4.120300e+02 3.726500e+02 +16 4070 2.046500e+02 5.385300e+02 +5 4071 -6.545500e+02 8.530300e+02 +7 4071 -7.868200e+02 6.942900e+02 +10 4071 -1.181710e+03 -4.093994e+01 +14 4071 -1.178000e+01 4.440300e+02 +18 4071 -1.305240e+03 3.220100e+02 +19 4071 6.518999e+02 6.905400e+02 +5 4072 4.359301e+02 7.495701e+02 +8 4072 -7.291400e+02 3.583600e+02 +5 4073 2.746700e+02 8.700300e+02 +7 4073 1.185800e+02 5.274900e+02 +5 4074 4.368101e+02 8.961899e+02 +8 4074 -6.765800e+02 6.596700e+02 +5 4075 8.179800e+02 6.562200e+02 +8 4075 3.859985e+00 -2.229980e+00 +5 4076 5.251000e+02 8.495900e+02 +8 4076 -5.061000e+02 5.050000e+02 +5 4077 4.626100e+02 8.746700e+02 +8 4077 -6.298400e+02 6.001100e+02 +5 4078 5.227700e+02 8.824000e+02 +8 4078 -5.041700e+02 5.621400e+02 +5 4079 -8.432200e+02 3.996200e+02 +7 4079 -1.026780e+03 2.455200e+02 +14 4079 -1.647800e+02 1.926600e+02 +16 4079 -5.453400e+02 2.498000e+02 +5 4080 7.143101e+02 7.427600e+02 +8 4080 -1.616600e+02 2.062700e+02 +5 4081 7.692500e+02 7.530400e+02 +8 4081 -6.038000e+01 2.016600e+02 +5 4082 3.403600e+02 8.200200e+02 +7 4082 1.705800e+02 4.676500e+02 +9 4082 -4.075300e+02 3.742100e+02 +10 4082 -3.050200e+02 -2.710900e+02 +5 4083 1.166801e+02 8.952700e+02 +7 4083 -8.677002e+01 5.893800e+02 +14 4083 3.958800e+02 3.660500e+02 +16 4083 1.834600e+02 5.293201e+02 +18 4083 -7.582700e+02 2.280100e+02 +5 4084 4.158000e+02 9.328400e+02 +8 4084 -7.079200e+02 7.330900e+02 +5 4085 8.223101e+02 6.515800e+02 +8 4085 1.206995e+01 -1.259998e+01 +5 4086 8.275601e+02 6.572200e+02 +8 4086 2.084998e+01 -4.179993e+00 +5 4087 6.892700e+02 6.661799e+02 +8 4087 -2.283000e+02 6.952002e+01 +5 4088 2.969200e+02 8.865000e+02 +6 4088 -7.530400e+02 5.662600e+02 +8 4088 -9.868200e+02 7.088700e+02 +5 4089 7.255699e+02 6.286899e+02 +8 4089 -1.690400e+02 -1.953003e+01 +5 4090 7.074600e+02 6.329100e+02 +8 4090 -2.028300e+02 -3.950012e+00 +5 4091 6.789500e+02 6.515100e+02 +8 4091 -2.525300e+02 4.372998e+01 +5 4092 7.233400e+02 7.494800e+02 +8 4092 -1.450000e+02 2.158100e+02 +5 4093 3.380200e+02 8.663500e+02 +8 4093 -9.032200e+02 6.483700e+02 +5 4094 5.533500e+02 8.675900e+02 +8 4094 -4.434400e+02 5.049500e+02 +5 4095 3.816700e+02 8.824399e+02 +8 4095 -8.029900e+02 6.604600e+02 +5 4096 8.170200e+02 6.422800e+02 +8 4096 -5.999756e-02 -2.678998e+01 +5 4097 7.975901e+02 6.819800e+02 +8 4097 -2.601001e+01 5.562000e+01 +5 4098 7.513199e+02 7.098000e+02 +8 4098 -1.014600e+02 1.275600e+02 +5 4099 7.513199e+02 7.098000e+02 +8 4099 -1.014600e+02 1.275600e+02 +5 4100 7.560200e+02 7.146600e+02 +8 4100 -9.275000e+01 1.351500e+02 +5 4101 7.476000e+02 7.629600e+02 +8 4101 -9.732001e+01 2.276600e+02 +5 4102 7.616899e+02 7.803600e+02 +8 4102 -6.678003e+01 2.575701e+02 +5 4103 4.492300e+02 7.893101e+02 +8 4103 -6.869200e+02 4.369000e+02 +5 4104 7.505900e+02 7.931799e+02 +8 4104 -8.401001e+01 2.869299e+02 +5 4105 7.528701e+02 8.021600e+02 +8 4105 -7.703003e+01 3.035601e+02 +5 4106 7.528701e+02 8.021600e+02 +8 4106 -7.703003e+01 3.035601e+02 +5 4107 6.823101e+02 8.306700e+02 +8 4107 -2.014100e+02 3.935100e+02 +5 4108 6.890200e+02 8.403400e+02 +8 4108 -1.853000e+02 4.084000e+02 +5 4109 3.885300e+02 8.418000e+02 +8 4109 -7.997200e+02 5.735200e+02 +5 4110 4.530500e+02 8.541899e+02 +8 4110 -6.579100e+02 5.668500e+02 +5 4111 4.118300e+02 8.564700e+02 +8 4111 -7.454400e+02 5.929900e+02 +5 4112 4.159301e+02 8.597700e+02 +8 4112 -7.358000e+02 5.984800e+02 +5 4113 4.101899e+02 8.662700e+02 +8 4113 -7.455700e+02 6.143101e+02 +5 4114 6.996500e+02 8.739500e+02 +7 4114 3.796300e+02 4.754299e+02 +12 4114 -7.518200e+02 -3.482500e+02 +13 4114 -1.387290e+03 1.038140e+03 +5 4115 7.016200e+02 8.775900e+02 +7 4115 3.829301e+02 4.783600e+02 +8 4115 -1.578200e+02 4.588201e+02 +5 4116 4.574399e+02 9.190200e+02 +8 4116 -6.266000e+02 6.932400e+02 +5 4117 1.194399e+02 9.544100e+02 +7 4117 -8.653003e+01 6.465601e+02 +10 4117 -5.559700e+02 -1.066200e+02 +12 4117 -1.212750e+03 -1.712000e+02 +16 4117 1.823600e+02 5.701600e+02 +5 4118 8.210200e+02 6.528201e+02 +8 4118 8.770020e+00 -9.289978e+00 +5 4119 7.944800e+02 6.838300e+02 +8 4119 -3.185999e+01 6.096997e+01 +5 4120 8.360601e+02 6.902300e+02 +8 4120 4.070996e+01 5.214001e+01 +5 4121 7.336400e+02 7.286000e+02 +8 4121 -1.305200e+02 1.729100e+02 +5 4122 7.638301e+02 7.879200e+02 +8 4122 -6.085999e+01 2.710800e+02 +5 4123 3.678600e+02 8.692500e+02 +8 4123 -8.374000e+02 6.418900e+02 +6 4124 -6.997000e+02 4.425100e+02 +8 4124 -9.230800e+02 5.773300e+02 +6 4125 9.509000e+02 -2.178900e+02 +8 4125 9.364500e+02 -7.419000e+01 +6 4126 9.200200e+02 -1.869700e+02 +7 4126 9.388401e+02 2.154600e+02 +16 4126 9.946500e+02 2.595800e+02 +6 4127 -3.340900e+02 -3.438000e+01 +7 4127 3.130699e+02 2.773401e+02 +6 4128 -8.106400e+02 1.325500e+02 +7 4128 1.308400e+02 3.248900e+02 +9 4128 -4.508500e+02 1.916500e+02 +6 4129 3.288800e+02 -2.314000e+02 +8 4129 6.231801e+02 -5.628003e+01 +16 4129 8.059700e+02 3.071500e+02 +6 4130 9.185800e+02 -8.863000e+01 +7 4130 9.376599e+02 2.623600e+02 +6 4131 8.251300e+02 3.896997e+01 +7 4131 8.970300e+02 3.276000e+02 +6 4132 4.258997e+01 -9.209003e+01 +8 4132 4.151001e+01 7.132001e+01 +6 4133 5.416003e+01 -6.060999e+01 +8 4133 5.652002e+01 1.141300e+02 +6 4134 7.813500e+02 -4.843400e+02 +8 4134 7.731899e+02 -3.783199e+02 +6 4135 3.150900e+02 -1.609300e+02 +8 4135 6.035800e+02 4.735999e+01 +6 4136 3.150900e+02 -1.609300e+02 +8 4136 6.035800e+02 4.735999e+01 +6 4137 3.124700e+02 -9.889001e+01 +8 4137 5.987000e+02 1.398300e+02 +6 4138 9.540400e+02 -9.571002e+01 +8 4138 9.339600e+02 6.469000e+01 +6 4139 9.266400e+02 -3.606000e+01 +7 4139 9.429199e+02 2.879900e+02 +8 4139 9.115000e+02 1.314800e+02 +12 4139 -1.878800e+02 -5.559000e+02 +17 4139 -8.661200e+02 3.409299e+02 +6 4140 9.698800e+02 1.053300e+02 +8 4140 9.473700e+02 2.920601e+02 +6 4141 9.881400e+02 2.186800e+02 +8 4141 9.671500e+02 4.223101e+02 +6 4142 -5.504200e+02 5.562200e+02 +8 4142 -7.668000e+02 7.245000e+02 +6 4143 2.751600e+02 -2.476900e+02 +8 4143 5.187800e+02 -8.615997e+01 +6 4144 9.123199e+02 -2.242900e+02 +8 4144 8.984200e+02 -8.091998e+01 +6 4145 2.722200e+02 -2.000100e+02 +8 4145 5.134800e+02 -1.842999e+01 +6 4146 3.404500e+02 -1.645300e+02 +8 4146 6.405300e+02 4.377002e+01 +6 4147 9.585200e+02 -1.175600e+02 +7 4147 9.537600e+02 2.464900e+02 +8 4147 9.370699e+02 3.621997e+01 +12 4147 -1.781500e+02 -5.975601e+02 +6 4148 9.239700e+02 -9.632001e+01 +8 4148 9.045800e+02 6.364001e+01 +6 4149 7.422998e+01 -9.064001e+01 +8 4149 9.183997e+01 8.052002e+01 +6 4150 -1.681800e+02 -5.178998e+01 +8 4150 -2.678100e+02 9.146002e+01 +6 4151 9.912400e+02 1.058800e+02 +7 4151 9.712000e+02 3.554199e+02 +8 4151 9.683900e+02 2.930200e+02 +17 4151 -7.950300e+02 4.955701e+02 +6 4152 2.718400e+02 -2.730000e+02 +8 4152 5.164399e+02 -1.221400e+02 +6 4153 2.723300e+02 -1.121200e+02 +8 4153 5.104399e+02 1.072100e+02 +6 4154 2.685100e+02 -1.042800e+02 +8 4154 5.036899e+02 1.189100e+02 +16 4154 7.584700e+02 3.805900e+02 +6 4155 9.816600e+02 -9.578003e+01 +8 4155 9.637100e+02 6.548999e+01 +12 4155 -1.659000e+02 -5.841801e+02 +17 4155 -8.041800e+02 2.700801e+02 +18 4155 7.615002e+01 -5.242004e+01 +6 4156 9.324301e+02 -9.158002e+01 +8 4156 9.122600e+02 6.837000e+01 +17 4156 -8.562800e+02 2.753301e+02 +6 4157 9.706300e+02 -9.098999e+01 +8 4157 9.523600e+02 7.033002e+01 +6 4158 1.939500e+02 -8.453998e+01 +8 4158 3.093800e+02 1.150800e+02 +6 4159 8.011100e+02 -4.890015e+00 +8 4159 7.886300e+02 1.672100e+02 +6 4160 -2.882001e+01 9.184998e+01 +8 4160 -8.401001e+01 2.869299e+02 +6 4161 9.578900e+02 1.044900e+02 +8 4161 9.337800e+02 2.911200e+02 +6 4162 -6.945000e+02 2.530700e+02 +8 4162 -9.062600e+02 3.703900e+02 +6 4163 1.829900e+02 -3.709800e+02 +8 4163 2.788900e+02 -2.693300e+02 +6 4164 8.060999e+01 -1.930700e+02 +8 4164 1.068600e+02 -4.958002e+01 +6 4165 1.379399e+02 -1.752500e+02 +8 4165 1.978900e+02 -1.877002e+01 +6 4166 -9.698999e+01 -1.730500e+02 +8 4166 -1.638800e+02 -4.609003e+01 +6 4167 6.991500e+02 -1.292000e+02 +8 4167 7.227100e+02 3.065997e+01 +6 4168 2.682700e+02 -1.121200e+02 +8 4168 5.039200e+02 1.072900e+02 +6 4169 9.216700e+02 -9.200000e+01 +8 4169 9.026000e+02 6.803998e+01 +6 4170 -1.315200e+02 -8.291998e+01 +8 4170 -2.121600e+02 6.084998e+01 +6 4171 -1.686500e+02 -7.038000e+01 +8 4171 -2.641300e+02 7.084998e+01 +6 4172 1.553003e+01 1.485999e+01 +8 4172 -7.849976e+00 2.030100e+02 +6 4173 -1.263000e+01 8.451001e+01 +8 4173 -6.014001e+01 2.796799e+02 +6 4174 -2.165002e+01 8.607001e+01 +8 4174 -7.202002e+01 2.813500e+02 +6 4175 8.122100e+02 2.183700e+02 +8 4175 7.904200e+02 4.227900e+02 +6 4176 -1.145900e+02 2.400800e+02 +8 4176 -2.093200e+02 4.520900e+02 +6 4177 -2.248700e+02 2.991100e+02 +8 4177 -3.444300e+02 5.194299e+02 +6 4178 -7.639900e+02 3.370700e+02 +8 4178 -9.863900e+02 4.560500e+02 +6 4179 2.697000e+02 -2.697800e+02 +8 4179 5.130000e+02 -1.176500e+02 +6 4180 -2.365002e+01 -1.929300e+02 +8 4180 -5.704999e+01 -6.197998e+01 +6 4181 3.096500e+02 -1.714900e+02 +8 4181 5.961700e+02 3.191998e+01 +6 4182 -9.934998e+01 -1.291400e+02 +8 4182 -1.644900e+02 8.330017e+00 +6 4183 2.613600e+02 -7.622998e+01 +8 4183 4.922500e+02 1.597900e+02 +6 4184 1.819000e+02 -6.835999e+01 +8 4184 2.928800e+02 1.372700e+02 +6 4185 -1.725600e+02 -5.171002e+01 +8 4185 -2.731200e+02 8.988000e+01 +6 4186 -3.295001e+01 -1.454999e+01 +8 4186 -8.047998e+01 1.551300e+02 +6 4187 -3.148999e+01 6.350000e+01 +8 4187 -8.371997e+01 2.520700e+02 +6 4188 -8.390002e+01 8.007001e+01 +8 4188 -1.568500e+02 2.643300e+02 +6 4189 -8.390002e+01 8.007001e+01 +8 4189 -1.568500e+02 2.643300e+02 +6 4190 -1.001200e+02 1.393500e+02 +8 4190 -1.840100e+02 3.332900e+02 +6 4191 9.488101e+02 1.987000e+02 +8 4191 9.275000e+02 3.997900e+02 +6 4192 -9.698999e+01 2.089400e+02 +8 4192 -1.862200e+02 4.158201e+02 +6 4193 7.645699e+02 2.640300e+02 +8 4193 7.494600e+02 4.800200e+02 +6 4194 -2.348700e+02 2.887700e+02 +8 4194 -3.559000e+02 5.067100e+02 +7 4195 9.199600e+02 3.935100e+02 +8 4195 8.511000e+02 3.801500e+02 +7 4196 9.582200e+02 2.607200e+02 +8 4196 9.463800e+02 6.792999e+01 +20 4196 6.747998e+01 -2.390200e+02 +7 4197 9.644800e+02 2.791699e+02 +8 4197 9.576300e+02 1.125100e+02 +17 4197 -8.085200e+02 3.173101e+02 +18 4197 7.489001e+01 -3.768994e+01 +20 4197 7.145996e+01 -2.272900e+02 +7 4198 9.638899e+02 4.051599e+02 +8 4198 9.490800e+02 4.056600e+02 +7 4199 9.539500e+02 4.922900e+02 +8 4199 9.610900e+02 5.612800e+02 +9 4199 5.258401e+02 4.116400e+02 +17 4199 -9.382800e+02 8.185000e+02 +20 4199 5.369995e+01 -8.653003e+01 +7 4200 9.652700e+02 2.638500e+02 +8 4200 9.614600e+02 7.726001e+01 +7 4201 9.592000e+02 4.206899e+02 +8 4201 9.388800e+02 4.429299e+02 +0 4202 -1.576110e+03 6.736000e+02 +7 4202 -1.293100e+03 7.221500e+02 +15 4202 4.641100e+02 4.285000e+02 +16 4202 -7.396300e+02 5.792500e+02 +19 4202 2.412000e+01 6.762300e+02 +0 4203 -1.362510e+03 6.808000e+02 +4 4203 -1.383800e+02 5.458800e+02 +5 4203 -9.876100e+02 8.115100e+02 +7 4203 -1.107060e+03 7.186300e+02 +14 4203 -1.958600e+02 4.683900e+02 +15 4203 5.942100e+02 4.371600e+02 +16 4203 -6.065100e+02 5.857100e+02 +0 4204 -1.509860e+03 8.177400e+02 +5 4204 -1.115330e+03 8.938400e+02 +14 4204 -2.743500e+02 5.363600e+02 +15 4204 4.964301e+02 5.155900e+02 +16 4204 -7.113100e+02 6.687200e+02 +19 4204 7.434998e+01 8.200601e+02 +0 4205 -1.575400e+03 6.212800e+02 +5 4205 -1.125200e+03 7.421300e+02 +0 4206 -1.361060e+03 6.299600e+02 +4 4206 -1.342600e+02 5.193101e+02 +5 4206 -9.737300e+02 7.764200e+02 +7 4206 -1.103930e+03 6.748400e+02 +14 4206 -1.947300e+02 4.447400e+02 +15 4206 5.985200e+02 4.088101e+02 +16 4206 -6.053700e+02 5.557800e+02 +0 4207 9.136201e+02 2.130500e+02 +4 4207 1.119980e+03 3.559700e+02 +5 4207 7.518700e+02 7.771200e+02 +0 4208 -1.215310e+03 7.279399e+02 +4 4208 -6.463000e+01 5.764900e+02 +7 4208 -9.970100e+02 7.553900e+02 +16 4208 -5.323300e+02 6.166899e+02 +0 4209 -1.399930e+03 7.386700e+02 +4 4209 -1.582400e+02 5.771700e+02 +5 4209 -1.023300e+03 8.505400e+02 +7 4209 -1.140750e+03 7.671200e+02 +14 4209 -2.167500e+02 4.966899e+02 +15 4209 5.706600e+02 4.719399e+02 +16 4209 -6.350100e+02 6.192300e+02 +19 4209 1.882200e+02 7.513101e+02 +20 4209 -1.360040e+03 1.302500e+02 +0 4210 -1.399930e+03 7.386700e+02 +4 4210 -1.582400e+02 5.771700e+02 +5 4210 -1.023300e+03 8.505400e+02 +7 4210 -1.140750e+03 7.671200e+02 +14 4210 -2.167500e+02 4.966899e+02 +15 4210 5.706600e+02 4.719399e+02 +16 4210 -6.350100e+02 6.192300e+02 +19 4210 1.882200e+02 7.513101e+02 +20 4210 -1.360040e+03 1.302500e+02 +0 4211 -1.434080e+03 9.212900e+02 +4 4211 -1.863300e+02 6.740701e+02 +7 4211 -1.198640e+03 9.233600e+02 +15 4211 5.356899e+02 5.772800e+02 +16 4211 -6.749900e+02 7.292500e+02 +19 4211 1.356700e+02 9.251000e+02 +20 4211 -1.402990e+03 2.465801e+02 +0 4212 1.116990e+03 1.948201e+02 +4 4212 1.295000e+03 3.795601e+02 +5 4212 9.724800e+02 8.216500e+02 +8 4212 2.677100e+02 2.133100e+02 +0 4213 -1.652740e+03 6.557900e+02 +4 4213 -2.868800e+02 5.296899e+02 +7 4213 -1.367040e+03 7.094500e+02 +14 4213 -3.412900e+02 4.607000e+02 +15 4213 4.189301e+02 4.158000e+02 +16 4213 -7.869600e+02 5.694100e+02 +19 4213 -4.988000e+01 6.518800e+02 +0 4214 -1.555710e+03 7.007500e+02 +7 4214 -1.283820e+03 7.438101e+02 +16 4214 -7.314300e+02 5.964600e+02 +19 4214 3.542004e+01 7.024500e+02 +0 4215 -1.398230e+03 7.051700e+02 +4 4215 -1.565100e+02 5.592700e+02 +5 4215 -1.015040e+03 8.263500e+02 +7 4215 -1.140690e+03 7.410000e+02 +14 4215 -2.165700e+02 4.811700e+02 +15 4215 5.715800e+02 4.512700e+02 +16 4215 -6.345000e+02 6.011700e+02 +19 4215 1.890000e+02 7.199200e+02 +0 4216 -1.606580e+03 7.295500e+02 +4 4216 -2.646600e+02 5.695800e+02 +7 4216 -1.328130e+03 7.698101e+02 +14 4216 -3.185100e+02 4.951300e+02 +15 4216 4.479700e+02 4.612100e+02 +16 4216 -7.621700e+02 6.134800e+02 +19 4216 -1.003003e+01 7.264399e+02 +0 4217 -1.339270e+03 7.676600e+02 +4 4217 -1.288101e+02 5.943201e+02 +5 4217 -9.846200e+02 8.801899e+02 +7 4217 -1.097440e+03 7.908800e+02 +14 4217 -1.909100e+02 5.094299e+02 +15 4217 6.034700e+02 4.913900e+02 +16 4217 -6.045600e+02 6.376200e+02 +19 4217 2.415900e+02 7.843000e+02 +20 4217 -1.326590e+03 1.456400e+02 +0 4218 -1.665760e+03 2.176200e+02 +5 4218 -1.124390e+03 4.443800e+02 +0 4219 -1.665760e+03 2.176200e+02 +5 4219 -1.124390e+03 4.443800e+02 +0 4220 -1.681830e+03 3.269900e+02 +5 4220 -1.153420e+03 5.192100e+02 +0 4221 -1.318670e+03 5.755400e+02 +5 4221 -9.390800e+02 7.413900e+02 +0 4222 -1.690840e+03 7.576899e+02 +5 4222 -1.232360e+03 8.287900e+02 +14 4222 -3.642200e+02 5.091000e+02 +15 4222 3.920400e+02 4.757200e+02 +16 4222 -8.230000e+02 6.306100e+02 +19 4222 -9.653003e+01 7.457600e+02 +0 4223 -1.430010e+03 7.818600e+02 +4 4223 -1.751500e+02 5.993900e+02 +5 4223 -1.051090e+03 8.782200e+02 +7 4223 -1.172590e+03 8.050800e+02 +14 4223 -2.331800e+02 5.175100e+02 +16 4223 -6.570500e+02 6.455900e+02 +19 4223 1.552500e+02 7.920200e+02 +0 4224 -1.638840e+03 7.951200e+02 +5 4224 -1.208610e+03 8.621600e+02 +0 4225 -1.491180e+03 8.026799e+02 +5 4225 -1.100510e+03 8.854200e+02 +14 4225 -2.650100e+02 5.277300e+02 +0 4226 1.089100e+03 1.272600e+02 +4 4226 1.259610e+03 3.234700e+02 +5 4226 9.356499e+02 7.494200e+02 +0 4227 -1.601510e+03 2.016599e+02 +5 4227 -1.076630e+03 4.408101e+02 +0 4228 -1.637820e+03 2.018301e+02 +5 4228 -1.102630e+03 4.359199e+02 +0 4229 -1.506350e+03 3.699199e+02 +5 4229 -1.034690e+03 5.712200e+02 +0 4230 -1.405380e+03 4.739299e+02 +4 4230 -1.537400e+02 4.385901e+02 +5 4230 -9.815300e+02 6.579600e+02 +7 4230 -1.132810e+03 5.510601e+02 +14 4230 -2.170300e+02 3.721300e+02 +19 4230 1.947900e+02 4.933600e+02 +20 4230 -1.364770e+03 -2.848999e+01 +0 4231 -1.379140e+03 5.723700e+02 +4 4231 -1.421801e+02 4.901500e+02 +5 4231 -9.795500e+02 7.304700e+02 +7 4231 -1.116200e+03 6.306000e+02 +14 4231 -2.056300e+02 4.174200e+02 +15 4231 5.879600e+02 3.728500e+02 +16 4231 -6.153100e+02 5.228700e+02 +19 4231 2.155100e+02 5.915701e+02 +0 4232 -1.662580e+03 5.925300e+02 +5 4232 -1.183930e+03 7.112400e+02 +0 4233 -1.615460e+03 5.942400e+02 +4 4233 -2.655200e+02 4.999000e+02 +5 4233 -1.150160e+03 7.189200e+02 +7 4233 -1.332410e+03 6.572500e+02 +14 4233 -3.229500e+02 4.310000e+02 +15 4233 4.449399e+02 3.826000e+02 +16 4233 -7.630600e+02 5.337400e+02 +19 4233 -1.590002e+01 5.961400e+02 +0 4234 -1.424140e+03 8.136500e+02 +5 4234 -1.053710e+03 9.024500e+02 +15 4234 5.509200e+02 5.150601e+02 +16 4234 -6.568300e+02 6.623300e+02 +19 4234 1.576899e+02 8.212500e+02 +20 4234 -1.384790e+03 1.776300e+02 +0 4235 -1.549020e+03 8.427800e+02 +4 4235 -2.402100e+02 6.321300e+02 +5 4235 -1.147100e+03 9.095601e+02 +7 4235 -1.287720e+03 8.639700e+02 +14 4235 -2.948000e+02 5.480200e+02 +15 4235 4.741200e+02 5.297300e+02 +16 4235 -7.366800e+02 6.828000e+02 +19 4235 3.560999e+01 8.387700e+02 +0 4236 -1.341190e+03 8.505500e+02 +5 4236 -1.003110e+03 9.428300e+02 +15 4236 5.961400e+02 5.418600e+02 +0 4237 1.097740e+03 2.241300e+02 +4 4237 1.280530e+03 3.968301e+02 +0 4238 -1.559750e+03 2.356100e+02 +5 4238 -1.050970e+03 4.693700e+02 +0 4239 1.554100e+03 2.390901e+02 +4 4239 1.485310e+03 3.545701e+02 +5 4239 1.176530e+03 8.510699e+02 +7 4239 8.952700e+02 3.657000e+02 +12 4239 -2.335100e+02 -4.814600e+02 +17 4239 -9.923000e+02 5.254700e+02 +0 4240 -1.373940e+03 3.302100e+02 +7 4240 -1.100230e+03 4.372600e+02 +16 4240 -6.021800e+02 3.848500e+02 +0 4241 -1.393850e+03 3.765000e+02 +4 4241 -1.461300e+02 3.877300e+02 +7 4241 -1.122250e+03 4.726699e+02 +14 4241 -2.115800e+02 3.265300e+02 +15 4241 5.830500e+02 2.587900e+02 +16 4241 -6.185300e+02 4.092800e+02 +19 4241 2.082700e+02 3.992200e+02 +0 4242 4.647500e+02 4.472400e+02 +8 4242 -8.675100e+02 6.748199e+02 +0 4243 -1.443680e+03 4.857400e+02 +4 4243 -1.744301e+02 4.439600e+02 +5 4243 -1.010250e+03 6.617900e+02 +7 4243 -1.169080e+03 5.617200e+02 +14 4243 -2.372500e+02 3.779600e+02 +15 4243 5.495200e+02 3.213700e+02 +16 4243 -6.503600e+02 4.717900e+02 +19 4243 1.558300e+02 5.026200e+02 +0 4244 -1.570210e+03 4.878201e+02 +5 4244 -1.100870e+03 6.476799e+02 +7 4244 -1.283500e+03 5.663201e+02 +15 4244 4.731801e+02 3.204000e+02 +16 4244 -7.286100e+02 4.707500e+02 +19 4244 3.241003e+01 4.969399e+02 +0 4245 -4.759200e+02 6.005400e+02 +9 4245 4.000900e+02 7.253003e+01 +0 4246 -1.170100e+03 7.600800e+02 +5 4246 -8.675900e+02 8.995200e+02 +0 4247 -1.237250e+03 7.796600e+02 +5 4247 -9.175800e+02 9.029900e+02 +15 4247 6.606500e+02 5.027500e+02 +0 4248 -1.257000e+03 7.813400e+02 +5 4248 -9.336300e+02 9.014500e+02 +0 4249 -1.361260e+03 8.178900e+02 +4 4249 -1.412300e+02 6.198400e+02 +5 4249 -1.009040e+03 9.138199e+02 +7 4249 -1.116920e+03 8.308300e+02 +15 4249 5.892200e+02 5.184000e+02 +16 4249 -6.188800e+02 6.664800e+02 +19 4249 2.184900e+02 8.311200e+02 +0 4250 -1.508530e+03 8.415701e+02 +5 4250 -1.117990e+03 9.133000e+02 +0 4251 1.113320e+03 8.970996e+01 +4 4251 1.276720e+03 2.987800e+02 +5 4251 9.603501e+02 7.218800e+02 +8 4251 2.468500e+02 6.165997e+01 +0 4252 1.124080e+03 9.819995e+01 +4 4252 1.285530e+03 3.056300e+02 +5 4252 9.707500e+02 7.309100e+02 +8 4252 2.638600e+02 7.359998e+01 +16 4252 6.995699e+02 3.295500e+02 +0 4253 1.552280e+03 1.229399e+02 +5 4253 1.184450e+03 7.632800e+02 +7 4253 8.919199e+02 2.892000e+02 +8 4253 8.019500e+02 1.299700e+02 +0 4254 9.964299e+02 1.959600e+02 +4 4254 1.183310e+03 3.555801e+02 +5 4254 8.318101e+02 7.846300e+02 +0 4255 -1.652430e+03 2.039199e+02 +5 4255 -1.111350e+03 4.363800e+02 +0 4256 -1.552880e+03 2.476000e+02 +5 4256 -1.048470e+03 4.787900e+02 +16 4256 -7.024100e+02 3.331700e+02 +19 4256 6.013000e+01 2.678401e+02 +0 4257 -1.560710e+03 2.570901e+02 +5 4257 -1.056740e+03 4.853600e+02 +14 4257 -2.931000e+02 2.726900e+02 +16 4257 -7.114700e+02 3.398300e+02 +0 4258 9.598501e+02 2.673900e+02 +4 4258 1.164580e+03 4.056000e+02 +5 4258 8.009800e+02 8.403900e+02 +8 4258 5.189941e+00 3.379900e+02 +16 4258 6.112600e+02 4.227000e+02 +0 4259 -1.555800e+03 3.644500e+02 +5 4259 -1.068850e+03 5.607500e+02 +0 4260 -1.403660e+03 4.596200e+02 +5 4260 -9.784200e+02 6.477000e+02 +7 4260 -1.132120e+03 5.393600e+02 +14 4260 -2.168800e+02 3.653200e+02 +16 4260 -6.251100e+02 4.572300e+02 +19 4260 1.958600e+02 4.793800e+02 +0 4261 -1.559490e+03 4.989299e+02 +5 4261 -1.095090e+03 6.565300e+02 +0 4262 -1.559490e+03 4.989299e+02 +5 4262 -1.095090e+03 6.565300e+02 +0 4263 -1.415930e+03 7.586200e+02 +5 4263 -1.037020e+03 8.631000e+02 +15 4263 5.622300e+02 4.821200e+02 +19 4263 1.705900e+02 7.691799e+02 +0 4264 -1.220320e+03 7.690100e+02 +4 4264 -7.055005e+01 5.991100e+02 +5 4264 -9.035600e+02 8.972100e+02 +7 4264 -1.007020e+03 7.894000e+02 +14 4264 -1.393600e+02 5.087400e+02 +15 4264 6.701500e+02 4.973700e+02 +16 4264 -5.391100e+02 6.415200e+02 +0 4265 -1.247590e+03 7.703600e+02 +5 4265 -9.224700e+02 8.948199e+02 +0 4266 -1.356330e+03 7.918101e+02 +5 4266 -9.991800e+02 8.945100e+02 +15 4266 5.954900e+02 5.033500e+02 +16 4266 -6.130000e+02 6.505000e+02 +19 4266 2.269800e+02 8.064500e+02 +0 4267 -1.625960e+03 8.227600e+02 +4 4267 -2.839900e+02 6.217700e+02 +5 4267 -1.202000e+03 8.861600e+02 +7 4267 -1.372560e+03 8.554700e+02 +14 4267 -3.381300e+02 5.400000e+02 +15 4267 4.221400e+02 5.165800e+02 +16 4267 -7.914000e+02 6.726899e+02 +19 4267 -4.456995e+01 8.133700e+02 +0 4268 -1.259470e+03 8.271700e+02 +4 4268 -9.476001e+01 6.309399e+02 +7 4268 -1.052690e+03 8.431200e+02 +14 4268 -1.628400e+02 5.373000e+02 +15 4268 6.402100e+02 5.317500e+02 +16 4268 -5.695500e+02 6.770300e+02 +19 4268 3.023199e+02 8.500400e+02 +0 4269 -1.331040e+03 8.325500e+02 +5 4269 -9.917200e+02 9.313101e+02 +0 4270 -1.484040e+03 1.016330e+03 +4 4270 -2.179301e+02 7.282700e+02 +7 4270 -1.260240e+03 1.013850e+03 +14 4270 -2.728900e+02 6.312500e+02 +15 4270 4.980900e+02 6.354100e+02 +0 4271 1.154970e+03 1.347700e+02 +4 4271 1.319530e+03 3.362300e+02 +0 4272 1.142330e+03 1.564099e+02 +4 4272 1.311550e+03 3.514099e+02 +5 4272 9.968000e+02 7.887300e+02 +8 4272 3.025400e+02 1.563900e+02 +10 4272 -7.787000e+01 -3.643000e+02 +13 4272 -1.046780e+03 5.575601e+02 +16 4272 7.048700e+02 3.716100e+02 +0 4273 1.013970e+03 1.581300e+02 +4 4273 1.195900e+03 3.334500e+02 +5 4273 8.517700e+02 7.563700e+02 +0 4274 1.683810e+03 1.837400e+02 +8 4274 9.803199e+02 2.186600e+02 +9 4274 5.750500e+02 1.997900e+02 +17 4274 -7.873400e+02 4.220601e+02 +0 4275 9.870400e+02 1.985300e+02 +5 4275 8.219900e+02 7.854700e+02 +0 4276 1.079630e+03 2.390300e+02 +4 4276 1.269140e+03 4.070801e+02 +5 4276 9.373000e+02 8.515300e+02 +8 4276 2.132800e+02 2.813201e+02 +0 4277 1.551910e+03 2.516799e+02 +4 4277 1.484290e+03 3.615200e+02 +16 4277 9.581200e+02 3.867400e+02 +0 4278 1.551910e+03 2.516799e+02 +4 4278 1.484290e+03 3.615200e+02 +5 4278 1.174640e+03 8.592300e+02 +8 4278 8.010100e+02 3.233400e+02 +16 4278 9.581200e+02 3.867400e+02 +0 4279 1.112970e+03 2.651799e+02 +4 4279 1.295400e+03 4.267000e+02 +0 4280 1.090560e+03 2.648401e+02 +4 4280 1.279710e+03 4.264399e+02 +0 4281 -1.381510e+03 3.885200e+02 +4 4281 -1.395500e+02 3.942700e+02 +7 4281 -1.108540e+03 4.821300e+02 +15 4281 5.907500e+02 2.659600e+02 +19 4281 2.214301e+02 4.117000e+02 +0 4282 -1.406910e+03 4.801899e+02 +4 4282 -1.549399e+02 4.410500e+02 +7 4282 -1.135850e+03 5.551600e+02 +14 4282 -2.185200e+02 3.746900e+02 +15 4282 5.734301e+02 3.186400e+02 +16 4282 -6.280000e+02 4.686799e+02 +19 4282 1.917400e+02 4.987200e+02 +0 4283 -1.437540e+03 5.627000e+02 +7 4283 -1.172050e+03 6.255400e+02 +14 4283 -2.365000e+02 4.145100e+02 +16 4283 -6.525100e+02 5.173900e+02 +19 4283 1.552500e+02 5.785100e+02 +0 4284 -1.594340e+03 5.966000e+02 +7 4284 -1.311170e+03 6.568600e+02 +14 4284 -3.117300e+02 4.314600e+02 +15 4284 4.566000e+02 3.827800e+02 +16 4284 -7.487300e+02 5.347100e+02 +19 4284 5.469971e+00 5.995100e+02 +0 4285 -1.393930e+03 6.811600e+02 +7 4285 -1.132330e+03 7.195400e+02 +14 4285 -2.131800e+02 4.692600e+02 +15 4285 5.763500e+02 4.375200e+02 +0 4286 -1.406580e+03 6.805500e+02 +4 4286 -1.597500e+02 5.463600e+02 +7 4286 -1.148060e+03 7.198500e+02 +19 4286 1.823400e+02 6.939200e+02 +0 4287 -1.365290e+03 7.178600e+02 +5 4287 -9.948300e+02 8.393800e+02 +0 4288 -1.256970e+03 7.213000e+02 +4 4288 -8.655005e+01 5.720601e+02 +5 4288 -9.198200e+02 8.569700e+02 +7 4288 -1.029930e+03 7.500100e+02 +14 4288 -1.536100e+02 4.864800e+02 +15 4288 6.525100e+02 4.666200e+02 +16 4288 -5.558800e+02 6.119399e+02 +19 4288 3.207600e+02 7.451400e+02 +0 4289 -1.288530e+03 7.235500e+02 +7 4289 -1.053610e+03 7.521600e+02 +14 4289 -1.671800e+02 4.877100e+02 +15 4289 6.349600e+02 4.665701e+02 +16 4289 -5.728400e+02 6.125000e+02 +19 4289 2.916600e+02 7.449299e+02 +0 4290 -1.320120e+03 7.264399e+02 +4 4290 -1.176200e+02 5.729500e+02 +5 4290 -9.641100e+02 8.518400e+02 +7 4290 -1.077890e+03 7.547300e+02 +15 4290 6.169800e+02 4.668000e+02 +16 4290 -5.903400e+02 6.134100e+02 +0 4291 -1.520950e+03 7.542300e+02 +5 4291 -1.111590e+03 8.463500e+02 +0 4292 -1.575720e+03 7.840400e+02 +5 4292 -1.154770e+03 8.613300e+02 +7 4292 -1.303970e+03 8.139000e+02 +14 4292 -3.042500e+02 5.201899e+02 +15 4292 4.629700e+02 4.927700e+02 +19 4292 1.590002e+01 7.808400e+02 +0 4293 -1.616560e+03 8.139100e+02 +4 4293 -2.788800e+02 6.170300e+02 +7 4293 -1.364580e+03 8.480701e+02 +14 4293 -3.334600e+02 5.350900e+02 +19 4293 -3.550000e+01 8.059100e+02 +0 4294 -1.478610e+03 8.661700e+02 +4 4294 -2.032800e+02 6.436200e+02 +5 4294 -1.100030e+03 9.344200e+02 +7 4294 -1.223820e+03 8.779100e+02 +15 4294 5.171700e+02 5.435500e+02 +0 4295 -1.226200e+03 9.022000e+02 +4 4295 -9.735999e+01 6.807400e+02 +7 4295 -1.075160e+03 9.189200e+02 +14 4295 -1.711900e+02 5.733101e+02 +15 4295 6.313000e+02 5.857900e+02 +19 4295 3.014500e+02 9.253101e+02 +20 4295 -1.327390e+03 2.445300e+02 +0 4296 -1.247780e+03 9.396001e+02 +4 4296 -1.154800e+02 7.079100e+02 +7 4296 -1.121240e+03 9.641899e+02 +15 4296 6.058101e+02 6.140900e+02 +19 4296 2.619399e+02 9.605500e+02 +0 4297 1.000040e+03 1.200601e+02 +5 4297 8.406299e+02 7.232500e+02 +0 4298 1.140880e+03 1.364600e+02 +4 4298 1.309810e+03 3.378201e+02 +0 4299 1.142830e+03 1.470601e+02 +5 4299 9.974199e+02 7.810200e+02 +12 4299 -6.434600e+02 -4.481400e+02 +16 4299 7.050400e+02 3.652800e+02 +0 4300 1.135370e+03 1.601200e+02 +4 4300 1.306570e+03 3.538101e+02 +5 4300 9.903999e+02 7.907300e+02 +8 4300 2.925000e+02 1.624000e+02 +12 4300 -6.491000e+02 -4.381600e+02 +16 4300 7.007000e+02 3.722200e+02 +0 4301 -1.596060e+03 1.633101e+02 +7 4301 -1.115770e+03 2.857100e+02 +0 4302 -1.619840e+03 1.703000e+02 +5 4302 -1.084400e+03 4.161100e+02 +0 4303 1.087450e+03 2.248401e+02 +4 4303 1.273850e+03 3.972400e+02 +5 4303 9.443601e+02 8.403400e+02 +8 4303 2.243101e+02 2.598300e+02 +0 4304 -1.387490e+03 2.802100e+02 +7 4304 -1.109410e+03 3.957200e+02 +14 4304 -2.078800e+02 2.817000e+02 +16 4304 -6.067600e+02 3.553300e+02 +19 4304 2.188400e+02 3.060701e+02 +0 4305 -1.376590e+03 2.858401e+02 +7 4305 -1.101540e+03 4.004500e+02 +14 4305 -2.034400e+02 2.844600e+02 +15 4305 5.949100e+02 2.063500e+02 +0 4306 -1.713870e+03 2.964500e+02 +5 4306 -1.169490e+03 4.934399e+02 +19 4306 -9.735999e+01 3.074299e+02 +0 4307 -1.552500e+03 2.998600e+02 +5 4307 -1.057340e+03 5.157500e+02 +19 4307 5.685999e+01 3.175901e+02 +0 4308 1.668750e+03 3.261300e+02 +5 4308 1.245780e+03 9.268500e+02 +8 4308 9.588700e+02 4.360500e+02 +0 4309 4.739800e+02 4.697300e+02 +8 4309 -8.500800e+02 7.097100e+02 +0 4310 4.866001e+02 4.834700e+02 +8 4310 -8.250100e+02 7.298700e+02 +0 4311 -1.585180e+03 4.938201e+02 +4 4311 -2.478600e+02 4.470601e+02 +7 4311 -1.296630e+03 5.725300e+02 +15 4311 4.644100e+02 3.244399e+02 +19 4311 1.893994e+01 5.022600e+02 +0 4312 -1.585180e+03 4.938201e+02 +4 4312 -2.478600e+02 4.470601e+02 +5 4312 -1.111430e+03 6.497500e+02 +7 4312 -1.296630e+03 5.725300e+02 +15 4312 4.644100e+02 3.244399e+02 +19 4312 1.893994e+01 5.022600e+02 +0 4313 -1.599470e+03 4.934500e+02 +4 4313 -2.552400e+02 4.466500e+02 +7 4313 -1.310000e+03 5.727500e+02 +0 4314 -1.599470e+03 4.934500e+02 +5 4314 -1.122320e+03 6.476600e+02 +0 4315 -1.377040e+03 4.987900e+02 +4 4315 -1.392100e+02 4.515400e+02 +7 4315 -1.109060e+03 5.704100e+02 +15 4315 5.911300e+02 3.304800e+02 +19 4315 2.212600e+02 5.193600e+02 +0 4316 -1.377040e+03 4.987900e+02 +4 4316 -1.392100e+02 4.515400e+02 +7 4316 -1.109060e+03 5.704100e+02 +15 4316 5.911300e+02 3.304800e+02 +19 4316 2.212600e+02 5.193600e+02 +0 4317 -1.376180e+03 5.102300e+02 +5 4317 -9.666900e+02 6.872600e+02 +14 4317 -2.032500e+02 3.885900e+02 +15 4317 5.918800e+02 3.372000e+02 +0 4318 -1.376180e+03 5.102300e+02 +5 4318 -9.666900e+02 6.872600e+02 +14 4318 -2.032500e+02 3.885900e+02 +15 4318 5.918800e+02 3.372000e+02 +0 4319 -4.156899e+02 5.208000e+02 +9 4319 4.307600e+02 3.731995e+01 +0 4320 -1.374790e+03 5.422300e+02 +4 4320 -1.394700e+02 4.739600e+02 +7 4320 -1.110550e+03 6.054200e+02 +14 4320 -2.032500e+02 4.034800e+02 +15 4320 5.922200e+02 3.560701e+02 +19 4320 2.207900e+02 5.615701e+02 +0 4321 -1.372290e+03 5.988500e+02 +4 4321 -1.394800e+02 5.041500e+02 +5 4321 -9.784600e+02 7.517400e+02 +7 4321 -1.111080e+03 6.516200e+02 +14 4321 -2.021600e+02 4.301300e+02 +15 4321 5.918800e+02 3.896400e+02 +16 4321 -6.125400e+02 5.382600e+02 +19 4321 2.208800e+02 6.170900e+02 +0 4322 -1.708820e+03 7.117900e+02 +5 4322 -1.236160e+03 7.916899e+02 +0 4323 -1.478400e+03 7.148201e+02 +5 4323 -1.073480e+03 8.225900e+02 +0 4324 -1.614340e+03 7.197700e+02 +4 4324 -2.693400e+02 5.650500e+02 +7 4324 -1.339060e+03 7.625800e+02 +14 4324 -3.239100e+02 4.902700e+02 +15 4324 4.403800e+02 4.548900e+02 +19 4324 -1.978003e+01 7.164700e+02 +0 4325 -1.105380e+03 7.261500e+02 +5 4325 -8.170000e+02 8.817100e+02 +0 4326 -1.363590e+03 7.300601e+02 +4 4326 -1.388600e+02 5.730900e+02 +7 4326 -1.109490e+03 7.572700e+02 +14 4326 -1.990200e+02 4.913400e+02 +15 4326 5.928700e+02 4.667100e+02 +19 4326 2.237300e+02 7.449000e+02 +0 4327 -1.524980e+03 7.793000e+02 +7 4327 -1.259540e+03 8.083800e+02 +14 4327 -2.804100e+02 5.168900e+02 +15 4327 4.919301e+02 4.916100e+02 +19 4327 6.303003e+01 7.792600e+02 +20 4327 -1.454410e+03 1.637000e+02 +0 4328 -1.356630e+03 7.828500e+02 +5 4328 -9.988800e+02 8.883199e+02 +7 4328 -1.109020e+03 8.034000e+02 +19 4328 2.264500e+02 7.991200e+02 +0 4329 -1.484150e+03 8.333700e+02 +4 4329 -2.054200e+02 6.266000e+02 +5 4329 -1.098980e+03 9.094700e+02 +7 4329 -1.226560e+03 8.510200e+02 +14 4329 -2.612000e+02 5.424399e+02 +15 4329 5.146300e+02 5.246300e+02 +19 4329 9.926001e+01 8.358900e+02 +0 4330 -1.524600e+03 8.641500e+02 +4 4330 -2.267300e+02 6.419000e+02 +5 4330 -1.131910e+03 9.269399e+02 +7 4330 -1.264580e+03 8.788600e+02 +15 4330 4.902300e+02 5.410400e+02 +16 4330 -7.215400e+02 6.936700e+02 +19 4330 5.929004e+01 8.621100e+02 +20 4330 -1.454480e+03 2.155901e+02 +0 4331 -1.470530e+03 8.739700e+02 +4 4331 -1.986100e+02 6.476400e+02 +5 4331 -1.095300e+03 9.409700e+02 +7 4331 -1.213840e+03 8.833500e+02 +15 4331 5.221400e+02 5.482100e+02 +16 4331 -6.875800e+02 6.995100e+02 +19 4331 1.119600e+02 8.764700e+02 +0 4332 -1.399790e+03 8.762000e+02 +5 4332 -1.045180e+03 9.517600e+02 +14 4332 -2.194100e+02 5.619200e+02 +19 4332 1.800699e+02 8.852000e+02 +0 4333 9.961499e+02 1.358700e+02 +5 4333 8.360200e+02 7.359700e+02 +16 4333 6.360400e+02 3.426600e+02 +0 4334 1.136350e+03 1.750801e+02 +4 4334 1.308190e+03 3.642200e+02 +0 4335 1.524030e+03 2.032900e+02 +2 4335 6.963101e+02 9.570001e+01 +3 4335 9.281899e+02 2.580300e+02 +4 4335 1.467940e+03 3.347100e+02 +5 4335 1.160050e+03 8.219700e+02 +17 4335 -1.047750e+03 4.730701e+02 +0 4336 -1.369250e+03 2.314299e+02 +7 4336 -1.092250e+03 3.573301e+02 +19 4336 2.380500e+02 2.590901e+02 +0 4337 -1.555870e+03 2.320000e+02 +5 4337 -1.049180e+03 4.679700e+02 +14 4337 -2.895800e+02 2.607200e+02 +15 4337 4.872700e+02 1.733800e+02 +19 4337 5.744995e+01 2.525901e+02 +0 4338 1.107510e+03 2.499800e+02 +4 4338 1.290910e+03 4.171300e+02 +0 4339 -1.355990e+03 3.618401e+02 +7 4339 -1.088780e+03 4.608301e+02 +16 4339 -5.929500e+02 4.023900e+02 +0 4340 -1.409810e+03 3.752300e+02 +5 4340 -9.696100e+02 5.867500e+02 +16 4340 -6.242400e+02 4.093800e+02 +19 4340 1.941100e+02 3.975200e+02 +0 4341 -1.583500e+03 5.159199e+02 +4 4341 -2.476200e+02 4.584199e+02 +7 4341 -1.297130e+03 5.909200e+02 +19 4341 1.946997e+01 5.234900e+02 +0 4342 -1.583500e+03 5.159199e+02 +4 4342 -2.476200e+02 4.584199e+02 +7 4342 -1.297130e+03 5.909200e+02 +15 4342 4.646400e+02 3.369800e+02 +19 4342 1.946997e+01 5.234900e+02 +0 4343 -1.679400e+03 5.750500e+02 +5 4343 -1.192030e+03 6.963101e+02 +0 4344 -1.189420e+03 5.929199e+02 +7 4344 -9.733500e+02 6.459200e+02 +0 4345 -1.443100e+03 5.961699e+02 +7 4345 -1.174020e+03 6.520200e+02 +14 4345 -2.370700e+02 4.298300e+02 +19 4345 1.512400e+02 6.095400e+02 +0 4346 -1.603160e+03 5.986699e+02 +5 4346 -1.141270e+03 7.231500e+02 +0 4347 -1.364370e+03 6.331799e+02 +5 4347 -9.758900e+02 7.760800e+02 +0 4348 -1.521840e+03 6.965601e+02 +4 4348 -2.208300e+02 5.539200e+02 +7 4348 -1.252090e+03 7.385300e+02 +15 4348 4.963900e+02 4.435701e+02 +16 4348 -7.099100e+02 5.945800e+02 +19 4348 6.905005e+01 7.013500e+02 +0 4349 -1.416010e+03 7.004000e+02 +7 4349 -1.156420e+03 7.367100e+02 +15 4349 5.612700e+02 4.481899e+02 +16 4349 -6.457900e+02 5.972100e+02 +19 4349 1.724200e+02 7.126799e+02 +0 4350 -1.195150e+03 7.370400e+02 +4 4350 -5.450000e+01 5.819200e+02 +7 4350 -9.813500e+02 7.615500e+02 +15 4350 6.889100e+02 4.782800e+02 +19 4350 3.794399e+02 7.653500e+02 +0 4351 -1.486490e+03 7.632400e+02 +5 4351 -1.088190e+03 8.571899e+02 +19 4351 1.001000e+02 7.648000e+02 +0 4352 -1.616060e+03 8.245200e+02 +7 4352 -1.364530e+03 8.558700e+02 +14 4352 -3.334200e+02 5.400800e+02 +0 4353 -1.476630e+03 8.544299e+02 +5 4353 -1.096640e+03 9.261801e+02 +7 4353 -1.218930e+03 8.684800e+02 +19 4353 1.067600e+02 8.576400e+02 +0 4354 -1.468330e+03 8.555701e+02 +4 4354 -1.974900e+02 6.383201e+02 +7 4354 -1.212410e+03 8.687900e+02 +15 4354 5.241200e+02 5.379800e+02 +16 4354 -6.859400e+02 6.886801e+02 +19 4354 1.138300e+02 8.590400e+02 +0 4355 -1.506250e+03 8.580100e+02 +5 4355 -1.117380e+03 9.251700e+02 +0 4356 -1.491070e+03 1.013710e+03 +7 4356 -1.266030e+03 1.011630e+03 +14 4356 -2.776300e+02 6.289500e+02 +19 4356 7.018994e+01 1.008850e+03 +0 4357 -1.485840e+03 1.048910e+03 +7 4357 -1.263360e+03 1.041410e+03 +19 4357 7.314001e+01 1.043080e+03 +0 4358 1.020260e+03 9.881006e+01 +5 4358 8.637700e+02 7.102900e+02 +0 4359 1.000480e+03 1.310300e+02 +4 4359 1.184820e+03 3.152600e+02 +5 4359 8.405200e+02 7.325300e+02 +0 4360 1.199560e+03 1.688900e+02 +4 4360 1.401570e+03 3.874700e+02 +5 4360 1.107380e+03 8.321300e+02 +8 4360 4.241600e+02 1.630400e+02 +0 4361 1.130710e+03 1.778900e+02 +4 4361 1.304090e+03 3.662700e+02 +5 4361 9.844299e+02 8.045100e+02 +8 4361 2.861100e+02 1.890100e+02 +0 4362 1.596600e+03 1.878301e+02 +5 4362 1.205840e+03 8.148900e+02 +8 4362 8.615800e+02 2.274400e+02 +0 4363 1.091870e+03 2.197800e+02 +4 4363 1.276550e+03 3.937200e+02 +0 4364 1.226900e+03 2.303101e+02 +4 4364 1.426090e+03 4.343201e+02 +0 4365 1.116810e+03 2.659600e+02 +5 4365 9.695200e+02 8.810100e+02 +8 4365 2.708400e+02 3.184900e+02 +0 4366 1.094960e+03 2.667200e+02 +5 4366 9.502300e+02 8.785699e+02 +8 4366 2.385500e+02 3.207800e+02 +0 4367 -1.414240e+03 3.755300e+02 +7 4367 -1.137360e+03 4.721799e+02 +19 4367 1.890800e+02 3.974000e+02 +0 4368 -1.592050e+03 6.468201e+02 +5 4368 -1.141540e+03 7.590100e+02 +7 4368 -1.309410e+03 6.990601e+02 +16 4368 -7.483100e+02 5.641600e+02 +19 4368 6.920044e+00 6.481899e+02 +0 4369 -1.396210e+03 6.527200e+02 +4 4369 -1.531200e+02 5.315100e+02 +5 4369 -1.003990e+03 7.876899e+02 +7 4369 -1.132360e+03 6.956899e+02 +15 4369 5.761700e+02 4.201400e+02 +19 4369 1.964200e+02 6.679900e+02 +0 4370 -1.227620e+03 7.511300e+02 +7 4370 -1.056380e+03 7.801500e+02 +0 4371 -1.253150e+03 7.528400e+02 +7 4371 -1.031090e+03 7.761799e+02 +19 4371 3.208199e+02 7.764200e+02 +0 4372 -1.259610e+03 7.539100e+02 +5 4372 -9.277100e+02 8.809100e+02 +0 4373 -1.427310e+03 7.654200e+02 +5 4373 -1.046260e+03 8.666899e+02 +19 4373 1.580200e+02 7.750100e+02 +0 4374 -1.440070e+03 7.716899e+02 +4 4374 -1.802800e+02 5.943000e+02 +7 4374 -1.181110e+03 7.967300e+02 +19 4374 1.450000e+02 7.797000e+02 +0 4375 -1.407320e+03 7.948900e+02 +4 4375 -1.641300e+02 6.069000e+02 +7 4375 -1.153280e+03 8.142400e+02 +19 4375 1.767900e+02 8.053101e+02 +0 4376 -1.359990e+03 7.977800e+02 +7 4376 -1.110230e+03 8.135000e+02 +19 4376 2.237300e+02 8.120300e+02 +0 4377 -1.520720e+03 8.482800e+02 +7 4377 -1.261310e+03 8.655900e+02 +15 4377 4.925200e+02 5.322900e+02 +19 4377 6.279004e+01 8.470400e+02 +0 4378 -1.493450e+03 8.574000e+02 +5 4378 -1.108660e+03 9.257500e+02 +0 4379 8.240500e+02 1.657600e+02 +8 4379 -1.464600e+02 1.726400e+02 +0 4380 1.111060e+03 2.604700e+02 +5 4380 9.646599e+02 8.753700e+02 +0 4381 8.730500e+02 3.237100e+02 +5 4381 7.091801e+02 8.657800e+02 +0 4382 1.100160e+03 3.271100e+02 +5 4382 9.499700e+02 9.320300e+02 +0 4383 1.097060e+03 3.319600e+02 +4 4383 1.286230e+03 4.734500e+02 +5 4383 9.467300e+02 9.360200e+02 +8 4383 2.426801e+02 4.166400e+02 +16 4383 6.760601e+02 4.817600e+02 +18 4383 -3.750100e+02 1.828800e+02 +0 4384 1.097020e+03 3.405701e+02 +4 4384 1.286270e+03 4.793401e+02 +0 4385 -1.391890e+03 4.542900e+02 +7 4385 -1.120820e+03 5.351500e+02 +19 4385 2.080900e+02 4.748800e+02 +0 4386 5.084299e+02 4.807100e+02 +9 4386 -3.559600e+02 4.773900e+02 +11 4386 2.973700e+02 4.054200e+02 +0 4387 -1.375870e+03 6.620300e+02 +7 4387 -1.117190e+03 7.028600e+02 +19 4387 2.141500e+02 6.782200e+02 +0 4388 -1.374970e+03 6.826899e+02 +7 4388 -1.118210e+03 7.202500e+02 +19 4388 2.138500e+02 6.986400e+02 +0 4389 -1.193990e+03 7.071000e+02 +7 4389 -9.828900e+02 7.380500e+02 +19 4389 3.793400e+02 7.354399e+02 +0 4390 4.853000e+02 4.747800e+02 +8 4390 -8.259700e+02 7.162500e+02 +1 4391 1.366900e+03 -3.600000e+01 +9 4391 6.499800e+02 1.351200e+02 +13 4391 1.358340e+03 1.745000e+02 +17 4391 -6.459500e+02 2.929900e+02 +1 4392 1.397070e+03 -3.098000e+02 +9 4392 6.588999e+02 1.775000e+01 +20 4392 1.211200e+02 -2.961500e+02 +1 4393 5.709800e+02 -6.556006e+01 +11 4393 9.460300e+02 1.591500e+02 +17 4393 -1.490790e+03 4.205000e+02 +1 4394 -9.491500e+02 -3.618500e+02 +9 4394 -3.172300e+02 -2.250000e+01 +1 4395 -9.491500e+02 -3.618500e+02 +11 4395 3.313400e+02 -7.633002e+01 +12 4395 -8.735600e+02 -6.890601e+02 +1 4396 -4.500000e+02 -2.142000e+02 +10 4396 -1.383600e+02 -4.895900e+02 +12 4396 -7.424000e+02 -6.054000e+02 +1 4397 -8.059200e+02 -1.334100e+02 +9 4397 -2.877000e+02 8.293994e+01 +13 4397 -1.665500e+03 7.869995e+01 +1 4398 -3.299700e+02 -2.278998e+01 +9 4398 -1.540200e+02 1.933500e+02 +11 4398 4.784100e+02 1.318500e+02 +13 4398 -1.183020e+03 3.585400e+02 +18 4398 -3.641801e+02 1.680054e+00 +1 4399 1.185090e+03 1.008401e+02 +9 4399 5.747100e+02 1.968301e+02 +17 4399 -7.877400e+02 4.111699e+02 +18 4399 8.218994e+01 -6.260010e+00 +1 4400 -1.424700e+02 -1.623800e+02 +9 4400 -1.032200e+02 1.719299e+02 +10 4400 -6.392004e+01 -4.409200e+02 +12 4400 -6.382200e+02 -5.361000e+02 +20 4400 -2.773300e+02 -2.073800e+02 +1 4401 5.444399e+02 -1.181300e+02 +11 4401 9.351400e+02 1.324200e+02 +1 4402 9.340801e+02 -9.529004e+01 +2 4402 7.249200e+02 -4.698999e+01 +3 4402 9.876499e+02 9.270020e+00 +4 4402 1.475740e+03 2.550100e+02 +5 4402 1.184000e+03 7.203500e+02 +8 4402 7.947100e+02 4.287000e+01 +1 4403 1.044640e+03 -1.567999e+01 +5 4403 1.213170e+03 7.565200e+02 +17 4403 -9.081800e+02 3.172400e+02 +1 4404 1.401310e+03 2.434099e+02 +9 4404 6.678000e+02 2.552200e+02 +20 4404 1.264000e+02 -1.698400e+02 +1 4405 -1.392840e+03 7.986300e+02 +9 4405 -4.933199e+02 4.445701e+02 +1 4406 -1.167230e+03 8.125800e+02 +9 4406 -4.127900e+02 4.568000e+02 +10 4406 -3.066300e+02 -2.121200e+02 +11 4406 2.450100e+02 3.856000e+02 +12 4406 -9.346700e+02 -3.063199e+02 +20 4406 -4.470100e+02 -5.227002e+01 +1 4407 -1.461760e+03 -4.443600e+02 +9 4407 -4.958500e+02 -6.491003e+01 +1 4408 -3.751700e+02 -1.741600e+02 +11 4408 4.661300e+02 5.187000e+01 +18 4408 -3.740300e+02 -4.895996e+01 +1 4409 5.415200e+02 -1.590800e+02 +11 4409 9.321801e+02 1.005400e+02 +1 4410 1.260050e+03 -9.937000e+01 +9 4410 6.054700e+02 1.069800e+02 +10 4410 4.200500e+02 -4.635900e+02 +1 4411 -1.453650e+03 4.684700e+02 +9 4411 -5.112200e+02 3.035200e+02 +1 4412 -1.453650e+03 4.684700e+02 +9 4412 -5.112200e+02 3.035200e+02 +1 4413 -1.369990e+03 6.696500e+02 +11 4413 1.767400e+02 3.180700e+02 +1 4414 -1.051360e+03 -4.438199e+02 +9 4414 -3.516700e+02 -5.847998e+01 +12 4414 -9.041700e+02 -7.167000e+02 +1 4415 -7.819300e+02 -3.872800e+02 +11 4415 3.687900e+02 -7.964001e+01 +18 4415 -4.486100e+02 -1.335100e+02 +1 4416 1.408270e+03 -3.733400e+02 +9 4416 6.636599e+02 -1.008997e+01 +1 4417 1.408270e+03 -3.733400e+02 +9 4417 6.636599e+02 -1.008997e+01 +1 4418 1.049790e+03 -3.237600e+02 +5 4418 1.222900e+03 6.299600e+02 +8 4418 8.657900e+02 -1.509800e+02 +1 4419 1.049790e+03 -3.237600e+02 +5 4419 1.222900e+03 6.299600e+02 +8 4419 8.657900e+02 -1.509800e+02 +1 4420 1.401160e+03 -2.606300e+02 +10 4420 4.610100e+02 -5.119399e+02 +18 4420 1.345000e+02 -1.050800e+02 +20 4420 1.228800e+02 -2.850100e+02 +1 4421 -1.416700e+02 -1.760400e+02 +9 4421 -1.028000e+02 1.596599e+02 +1 4422 2.893300e+02 -1.149301e+02 +9 4422 8.179004e+01 4.281599e+02 +10 4422 8.967004e+01 -3.230699e+02 +11 4422 6.517900e+02 3.552400e+02 +1 4423 1.404770e+03 1.040002e+01 +9 4423 6.659399e+02 1.541500e+02 +10 4423 4.620000e+02 -4.284900e+02 +12 4423 -8.851001e+01 -5.596801e+02 +13 4423 1.411230e+03 2.352600e+02 +17 4423 -6.143199e+02 3.300000e+02 +18 4423 1.381801e+02 -3.365002e+01 +20 4423 1.255000e+02 -2.232300e+02 +1 4424 1.033750e+03 1.968000e+02 +2 4424 7.832700e+02 1.135600e+02 +5 4424 1.201360e+03 8.437800e+02 +8 4424 8.588300e+02 2.869200e+02 +12 4424 -2.064700e+02 -4.934301e+02 +16 4424 9.806500e+02 3.720300e+02 +17 4424 -9.104600e+02 4.974800e+02 +1 4425 1.390610e+03 3.666500e+02 +10 4425 4.577600e+02 -3.190800e+02 +13 4425 1.414000e+03 7.312600e+02 +17 4425 -6.172200e+02 6.272500e+02 +18 4425 1.393000e+02 6.220996e+01 +20 4425 1.251300e+02 -1.414500e+02 +1 4426 -1.129180e+03 -4.608400e+02 +9 4426 -3.759100e+02 -6.765002e+01 +1 4427 1.527000e+02 -3.978900e+02 +9 4427 1.749900e+02 -6.814001e+01 +11 4427 8.385800e+02 -1.230800e+02 +18 4427 -1.743600e+02 -1.658700e+02 +1 4428 -9.627500e+02 -3.972600e+02 +9 4428 -3.231100e+02 -3.742004e+01 +1 4429 1.395910e+03 -2.992900e+02 +10 4429 4.589199e+02 -5.240699e+02 +12 4429 -9.523999e+01 -6.637000e+02 +17 4429 -6.270400e+02 7.598999e+01 +18 4429 1.323700e+02 -1.156100e+02 +1 4430 1.015840e+03 -2.767000e+02 +3 4430 1.078930e+03 -1.739600e+02 +5 4430 1.210730e+03 6.476899e+02 +8 4430 8.420200e+02 -1.106000e+02 +1 4431 1.395510e+03 -6.333997e+01 +9 4431 6.620100e+02 1.228500e+02 +10 4431 4.594099e+02 -4.517700e+02 +13 4431 1.396680e+03 1.344199e+02 +17 4431 -6.236100e+02 2.692700e+02 +18 4431 1.353300e+02 -5.318005e+01 +1 4432 -1.467970e+03 -5.750000e+00 +11 4432 1.537900e+02 5.015002e+01 +1 4433 1.386270e+03 1.534000e+02 +10 4433 4.567000e+02 -3.843900e+02 +12 4433 -9.216003e+01 -5.102800e+02 +13 4433 1.396500e+03 4.366699e+02 +17 4433 -6.257500e+02 4.509900e+02 +18 4433 1.355100e+02 5.380005e+00 +1 4434 1.384470e+03 1.830701e+02 +9 4434 6.608301e+02 2.295000e+02 +13 4434 1.396970e+03 4.762000e+02 +18 4434 1.357000e+02 1.250000e+01 +1 4435 1.384470e+03 1.830701e+02 +9 4435 6.608301e+02 2.295000e+02 +13 4435 1.396970e+03 4.762000e+02 +17 4435 -6.260500e+02 4.741599e+02 +18 4435 1.357000e+02 1.250000e+01 +1 4436 -5.656000e+02 2.409000e+02 +9 4436 -2.221300e+02 2.807000e+02 +11 4436 4.185601e+02 2.164400e+02 +13 4436 -1.421540e+03 6.856600e+02 +1 4437 1.202050e+03 4.471000e+02 +8 4437 1.000570e+03 5.014600e+02 +1 4438 -1.138770e+03 -4.257300e+02 +11 4438 2.713199e+02 -1.052100e+02 +1 4439 1.344020e+03 -3.079700e+02 +9 4439 6.366201e+02 1.775000e+01 +1 4440 1.438030e+03 -2.981300e+02 +10 4440 4.712100e+02 -5.234900e+02 +12 4440 -8.192004e+01 -6.631200e+02 +17 4440 -5.937900e+02 7.672998e+01 +1 4441 -1.196810e+03 -2.722100e+02 +9 4441 -4.018900e+02 7.079956e+00 +1 4442 5.443899e+02 -2.346300e+02 +11 4442 9.338600e+02 5.892999e+01 +1 4443 5.478799e+02 -1.969100e+02 +11 4443 9.376200e+02 7.922998e+01 +1 4444 1.259410e+03 -8.757996e+01 +9 4444 6.058601e+02 1.123500e+02 +1 4445 -9.864001e+01 3.220996e+01 +11 4445 5.093000e+02 2.526000e+02 +13 4445 -9.699600e+02 6.388401e+02 +1 4446 1.373400e+03 1.382000e+02 +9 4446 6.564099e+02 2.105100e+02 +17 4446 -6.343300e+02 4.371799e+02 +1 4447 1.379690e+03 2.097700e+02 +9 4447 6.566101e+02 2.398900e+02 +13 4447 1.387050e+03 5.110500e+02 +1 4448 1.423810e+03 3.919900e+02 +10 4448 4.673501e+02 -3.112100e+02 +13 4448 1.458650e+03 7.651100e+02 +17 4448 -5.897200e+02 6.469399e+02 +1 4449 -1.174310e+03 4.110400e+02 +9 4449 -4.045100e+02 2.869299e+02 +1 4450 -1.129410e+03 5.794700e+02 +11 4450 2.610900e+02 2.930700e+02 +1 4451 -1.376170e+03 7.943000e+02 +9 4451 -4.874900e+02 4.416200e+02 +11 4451 1.726899e+02 3.691300e+02 +1 4452 -1.005560e+03 8.267600e+02 +9 4452 -3.559600e+02 4.773900e+02 +1 4453 -9.656700e+02 -4.440699e+02 +9 4453 -3.265900e+02 -5.663000e+01 +1 4454 5.240200e+02 -4.340300e+02 +11 4454 9.227500e+02 -5.634003e+01 +1 4455 -1.038990e+03 -4.268600e+02 +9 4455 -3.484301e+02 -5.087000e+01 +1 4456 4.972400e+02 -4.211200e+02 +11 4456 9.060800e+02 -4.967999e+01 +1 4457 5.132400e+02 -3.776700e+02 +11 4457 9.164100e+02 -2.464001e+01 +1 4458 -1.048000e+02 -3.449399e+02 +5 4458 9.905601e+02 6.063700e+02 +1 4459 5.646699e+02 -1.543800e+02 +11 4459 9.481500e+02 9.821002e+01 +1 4460 5.641001e+02 -1.429301e+02 +11 4460 9.479000e+02 1.065100e+02 +1 4461 -1.185800e+02 -9.864001e+01 +11 4461 5.195500e+02 1.550900e+02 +13 4461 -9.677500e+02 3.505400e+02 +1 4462 1.035470e+03 -7.244995e+01 +2 4462 7.830900e+02 -3.723999e+01 +3 4462 1.098440e+03 3.209998e+01 +5 4462 1.213640e+03 7.319100e+02 +8 4462 8.634600e+02 6.015002e+01 +12 4462 -2.070800e+02 -5.847700e+02 +17 4462 -9.146900e+02 2.693101e+02 +1 4463 1.412040e+03 -6.033997e+01 +9 4463 6.689500e+02 1.237500e+02 +13 4463 1.417880e+03 1.370901e+02 +17 4463 -6.100601e+02 2.709299e+02 +1 4464 1.287570e+03 -2.656006e+01 +9 4464 6.168501e+02 1.385801e+02 +12 4464 -1.263000e+02 -5.711801e+02 +13 4464 1.253320e+03 1.885701e+02 +17 4464 -7.077400e+02 3.015901e+02 +1 4465 -1.629700e+02 1.335100e+02 +11 4465 4.674700e+02 3.157900e+02 +13 4465 -1.096630e+03 8.425200e+02 +1 4466 1.321910e+03 2.058000e+02 +9 4466 6.337500e+02 2.390801e+02 +13 4466 1.312740e+03 5.094199e+02 +17 4466 -6.742000e+02 4.936300e+02 +1 4467 1.408100e+03 2.100601e+02 +10 4467 4.620100e+02 -3.675900e+02 +12 4467 -8.578003e+01 -4.928700e+02 +13 4467 1.425370e+03 5.106100e+02 +17 4467 -6.064399e+02 4.938201e+02 +18 4467 1.405200e+02 1.955005e+01 +1 4468 1.438540e+03 2.105100e+02 +9 4468 6.824500e+02 2.401000e+02 +13 4468 1.466140e+03 5.098600e+02 +17 4468 -5.822600e+02 4.932000e+02 +1 4469 1.429990e+03 2.106100e+02 +9 4469 6.785901e+02 2.400901e+02 +1 4470 1.246220e+03 3.369000e+02 +9 4470 6.039399e+02 2.982400e+02 +13 4470 1.218110e+03 7.005200e+02 +1 4471 1.392170e+03 3.564800e+02 +9 4471 6.655000e+02 3.052400e+02 +12 4471 -8.657996e+01 -4.426000e+02 +13 4471 1.416190e+03 7.180900e+02 +17 4471 -6.153900e+02 6.186599e+02 +1 4472 1.193760e+03 4.898101e+02 +7 4472 1.102620e+03 5.529299e+02 +9 4472 6.627200e+02 5.020400e+02 +12 4472 -5.633997e+01 -2.921500e+02 +17 4472 -7.962300e+02 9.377200e+02 +18 4472 1.444100e+02 1.795701e+02 +1 4473 1.180670e+03 4.899700e+02 +7 4473 1.096890e+03 5.528201e+02 +9 4473 6.554199e+02 5.020300e+02 +10 4473 4.454600e+02 -2.050900e+02 +12 4473 -6.216003e+01 -2.921300e+02 +17 4473 -8.104400e+02 9.385300e+02 +18 4473 1.385800e+02 1.790901e+02 +1 4474 1.200790e+03 4.968800e+02 +9 4474 6.658501e+02 5.056400e+02 +12 4474 -5.420996e+01 -2.894000e+02 +17 4474 -7.909100e+02 9.443899e+02 +1 4475 1.076320e+03 5.149100e+02 +10 4475 4.078701e+02 -1.955100e+02 +1 4476 1.494910e+03 5.257700e+02 +8 4476 1.019650e+03 5.238900e+02 +1 4477 -9.104300e+02 5.500701e+02 +11 4477 3.280300e+02 3.006000e+02 +1 4478 -1.221390e+03 7.058101e+02 +9 4478 -4.264700e+02 4.084399e+02 +1 4479 -1.323700e+03 7.883101e+02 +11 4479 1.900200e+02 3.689800e+02 +1 4480 5.198300e+02 -3.854500e+02 +11 4480 9.204399e+02 -2.910999e+01 +1 4481 1.481680e+03 -3.790900e+02 +9 4481 6.940901e+02 -1.222998e+01 +1 4482 1.284790e+03 -3.540699e+02 +9 4482 6.124500e+02 -1.489990e+00 +1 4483 -1.190400e+02 -5.704004e+01 +5 4483 1.008090e+03 7.650300e+02 +1 4484 1.291610e+03 -2.222998e+01 +9 4484 6.194800e+02 1.410701e+02 +1 4485 -1.220300e+03 -1.002002e+01 +9 4485 -4.175200e+02 1.136500e+02 +1 4486 -8.588000e+01 2.034003e+01 +11 4486 5.177900e+02 2.446600e+02 +1 4487 -1.831300e+02 1.576400e+02 +11 4487 4.479301e+02 3.389300e+02 +13 4487 -1.148810e+03 9.094099e+02 +1 4488 -8.642700e+02 7.253000e+02 +11 4488 3.357000e+02 3.842200e+02 +1 4489 -1.025220e+03 7.844600e+02 +9 4489 -3.636801e+02 4.586799e+02 +11 4489 2.899700e+02 3.873201e+02 +1 4490 -1.025220e+03 7.844600e+02 +9 4490 -3.636801e+02 4.586799e+02 +1 4491 -1.177220e+03 9.049000e+02 +9 4491 -4.160800e+02 4.964500e+02 +1 4492 5.972200e+02 -1.623900e+02 +11 4492 9.674301e+02 9.047998e+01 +1 4493 1.355280e+03 -3.960022e+00 +9 4493 6.454700e+02 1.485200e+02 +10 4493 4.471101e+02 -4.339000e+02 +17 4493 -6.538500e+02 3.190601e+02 +1 4494 -1.476000e+02 7.940002e+00 +5 4494 9.895000e+02 7.966600e+02 +1 4495 -1.206700e+02 7.546997e+01 +9 4495 -1.210100e+02 3.498700e+02 +11 4495 4.936899e+02 2.811600e+02 +13 4495 -1.015590e+03 7.299500e+02 +1 4496 -1.822500e+02 1.696100e+02 +9 4496 -1.660100e+02 4.175801e+02 +1 4497 1.029830e+03 4.607500e+02 +8 4497 9.685601e+02 5.323900e+02 +17 4497 -9.272700e+02 7.864100e+02 +1 4498 1.562700e+02 -2.479800e+02 +11 4498 5.354800e+02 2.132400e+02 +13 4498 -6.700400e+02 2.925500e+02 +1 4499 1.562700e+02 -2.479800e+02 +11 4499 5.354800e+02 2.132400e+02 +1 4500 -4.698999e+01 -2.454999e+01 +11 4500 3.761100e+02 3.855900e+02 +1 4501 -1.267600e+02 8.745996e+01 +11 4501 4.896000e+02 2.880700e+02 +1 4502 -1.772200e+02 1.341400e+02 +11 4502 4.582500e+02 3.173200e+02 +13 4502 -1.124930e+03 8.480100e+02 +1 4503 -2.113300e+02 2.357100e+02 +9 4503 -1.869600e+02 4.617900e+02 +1 4504 1.053240e+03 4.785500e+02 +8 4504 9.915699e+02 5.501799e+02 +1 4505 3.088900e+02 -3.891003e+01 +9 4505 1.020699e+02 5.039700e+02 +13 4505 -2.557800e+02 8.834299e+02 +2 4506 -4.196500e+02 1.534998e+01 +11 4506 2.290000e+02 8.948999e+01 +2 4507 -5.033200e+02 2.939400e+02 +9 4507 -4.927400e+02 3.551300e+02 +11 4507 1.681600e+02 2.864500e+02 +2 4508 -4.218400e+02 2.871900e+02 +9 4508 -4.298800e+02 3.552600e+02 +11 4508 2.274700e+02 2.859300e+02 +2 4509 -4.218400e+02 2.871900e+02 +9 4509 -4.298800e+02 3.552600e+02 +10 4509 -3.201300e+02 -2.856000e+02 +11 4509 2.274700e+02 2.859300e+02 +12 4509 -9.523200e+02 -3.850300e+02 +2 4510 -4.795000e+02 -1.047300e+02 +11 4510 1.865300e+02 -1.799988e+00 +2 4511 -4.845200e+02 1.285400e+02 +9 4511 -4.793900e+02 2.360400e+02 +10 4511 -3.573199e+02 -3.714301e+02 +11 4511 1.809301e+02 1.667000e+02 +12 4511 -9.994500e+02 -4.812500e+02 +16 4511 3.223400e+02 3.550300e+02 +2 4512 -2.019500e+02 2.324200e+02 +9 4512 -2.468000e+02 3.351200e+02 +11 4512 3.975200e+02 2.704200e+02 +18 4512 -4.184399e+02 9.734009e+01 +20 4512 -3.572800e+02 -1.155800e+02 +2 4513 -1.984000e+02 2.959000e+02 +9 4513 -2.314000e+02 4.012600e+02 +2 4514 -4.430000e+02 4.290400e+02 +10 4514 -3.343500e+02 -2.090300e+02 +2 4515 -3.096800e+02 -8.560999e+01 +9 4515 -3.399399e+02 7.435999e+01 +11 4515 3.106500e+02 1.492999e+01 +12 4515 -8.876300e+02 -6.150800e+02 +2 4516 -2.563700e+02 -8.799988e+00 +9 4516 -2.964700e+02 1.344700e+02 +10 4516 -2.235500e+02 -4.454700e+02 +11 4516 3.517000e+02 7.458002e+01 +2 4517 -1.276500e+02 5.582001e+01 +9 4517 -1.741300e+02 2.025200e+02 +10 4517 -1.267700e+02 -4.068400e+02 +11 4517 4.587900e+02 1.396900e+02 +13 4517 -1.256270e+03 3.948301e+02 +18 4517 -3.778900e+02 6.790039e+00 +20 4517 -3.199600e+02 -1.916400e+02 +2 4518 4.891600e+02 8.181000e+01 +11 4518 9.696700e+02 1.729300e+02 +17 4518 -1.427690e+03 4.681300e+02 +2 4519 -2.859600e+02 8.363000e+01 +9 4519 -3.202700e+02 2.023500e+02 +10 4519 -2.429399e+02 -3.929800e+02 +11 4519 3.286500e+02 1.408700e+02 +12 4519 -8.671300e+02 -5.069600e+02 +18 4519 -4.743900e+02 9.160034e+00 +2 4520 -5.707600e+02 2.405100e+02 +9 4520 -5.485800e+02 3.144199e+02 +2 4521 7.264900e+02 3.529200e+02 +7 4521 9.883701e+02 5.150801e+02 +12 4521 -1.607900e+02 -3.241500e+02 +17 4521 -1.050240e+03 8.656899e+02 +20 4521 5.607996e+01 -6.193994e+01 +2 4522 -7.532300e+02 4.080800e+02 +9 4522 -6.841300e+02 4.437600e+02 +11 4522 -1.313000e+01 3.677100e+02 +18 4522 -6.976900e+02 1.653101e+02 +2 4523 4.807600e+02 -3.672300e+02 +9 4523 -4.778003e+01 -2.050601e+02 +13 4523 -1.261370e+03 -4.689399e+02 +2 4524 5.987300e+02 -3.204400e+02 +11 4524 7.734800e+02 -2.231000e+02 +2 4525 7.191600e+02 -2.992999e+01 +4 4525 1.472300e+03 2.649399e+02 +5 4525 1.178100e+03 7.326100e+02 +7 4525 8.840000e+02 2.628101e+02 +16 4525 9.506000e+02 2.979500e+02 +2 4526 7.191600e+02 -2.992999e+01 +3 4526 9.807500e+02 4.001001e+01 +4 4526 1.472300e+03 2.649399e+02 +5 4526 1.178100e+03 7.326100e+02 +7 4526 8.840000e+02 2.628101e+02 +8 4526 7.860100e+02 6.840002e+01 +12 4526 -2.412900e+02 -5.788199e+02 +16 4526 9.506000e+02 2.979500e+02 +2 4527 -4.192200e+02 1.609003e+01 +11 4527 2.296000e+02 9.057001e+01 +12 4527 -9.569800e+02 -5.478700e+02 +18 4527 -5.414500e+02 -2.068005e+01 +20 4527 -4.603000e+02 -2.164600e+02 +2 4528 -4.192200e+02 1.609003e+01 +11 4528 2.296000e+02 9.057001e+01 +12 4528 -9.569800e+02 -5.478700e+02 +18 4528 -5.414500e+02 -2.068005e+01 +2 4529 -4.178900e+02 1.244000e+02 +9 4529 -4.244900e+02 2.279000e+02 +10 4529 -3.200699e+02 -3.735200e+02 +12 4529 -9.554700e+02 -4.869000e+02 +2 4530 5.221500e+02 2.247600e+02 +11 4530 9.970800e+02 2.919400e+02 +17 4530 -1.368380e+03 6.832800e+02 +2 4531 -1.657200e+02 2.470500e+02 +9 4531 -2.138600e+02 3.483900e+02 +10 4531 -1.556500e+02 -3.032900e+02 +11 4531 4.239100e+02 2.801800e+02 +12 4531 -7.572800e+02 -3.960400e+02 +13 4531 -1.371970e+03 8.769200e+02 +18 4531 -4.025400e+02 9.865002e+01 +20 4531 -3.397500e+02 -1.129000e+02 +2 4532 -4.219700e+02 2.628900e+02 +9 4532 -4.295000e+02 3.361500e+02 +10 4532 -3.212900e+02 -2.978300e+02 +11 4532 2.270100e+02 2.672000e+02 +12 4532 -9.545100e+02 -4.019200e+02 +18 4532 -5.409100e+02 9.425000e+01 +2 4533 -4.785400e+02 2.642300e+02 +10 4533 -3.526000e+02 -2.983400e+02 +11 4533 1.847000e+02 2.662300e+02 +20 4533 -4.833900e+02 -1.179301e+02 +2 4534 -4.785400e+02 2.642300e+02 +9 4534 -4.730100e+02 3.332700e+02 +10 4534 -3.526000e+02 -2.983400e+02 +11 4534 1.847000e+02 2.662300e+02 +16 4534 3.256000e+02 4.172700e+02 +18 4534 -5.740400e+02 9.427002e+01 +20 4534 -4.833900e+02 -1.179301e+02 +2 4535 -6.554400e+02 2.640300e+02 +9 4535 -6.068000e+02 3.334700e+02 +2 4536 -6.554400e+02 2.640300e+02 +9 4536 -6.068000e+02 3.334700e+02 +2 4537 -5.457000e+02 3.283600e+02 +9 4537 -5.251400e+02 3.818401e+02 +11 4537 1.357200e+02 3.105000e+02 +12 4537 -1.029770e+03 -3.647500e+02 +2 4538 -4.178000e+02 3.980400e+02 +9 4538 -4.278500e+02 4.386000e+02 +10 4538 -3.187200e+02 -2.256200e+02 +11 4538 2.290100e+02 3.669800e+02 +12 4538 -9.482600e+02 -3.206801e+02 +18 4538 -5.374600e+02 1.580801e+02 +20 4538 -4.562700e+02 -6.214001e+01 +2 4539 -4.178000e+02 3.980400e+02 +9 4539 -4.278500e+02 4.386000e+02 +10 4539 -3.187200e+02 -2.256200e+02 +11 4539 2.290100e+02 3.669800e+02 +12 4539 -9.482600e+02 -3.206801e+02 +18 4539 -5.374600e+02 1.580801e+02 +20 4539 -4.562700e+02 -6.214001e+01 +2 4540 -6.027900e+02 4.038100e+02 +9 4540 -5.694400e+02 4.387200e+02 +2 4541 7.646000e+02 4.183500e+02 +7 4541 1.021180e+03 5.591799e+02 +9 4541 5.597400e+02 5.116500e+02 +12 4541 -1.321600e+02 -2.831300e+02 +18 4541 8.380005e+01 1.874600e+02 +20 4541 7.559998e+01 -3.384998e+01 +2 4542 7.646000e+02 4.183500e+02 +7 4542 1.021180e+03 5.591799e+02 +2 4543 -4.172600e+02 4.515100e+02 +9 4543 -4.282800e+02 4.789199e+02 +10 4543 -3.183900e+02 -1.975699e+02 +11 4543 2.289399e+02 4.053600e+02 +12 4543 -9.471200e+02 -2.916600e+02 +20 4543 -4.562100e+02 -4.091003e+01 +2 4544 -6.162900e+02 5.562400e+02 +11 4544 8.222998e+01 4.982400e+02 +2 4545 5.129399e+02 -3.247700e+02 +9 4545 -2.685999e+01 -1.809700e+02 +2 4546 -4.474100e+02 -2.164400e+02 +9 4546 -4.487200e+02 -2.884998e+01 +10 4546 -3.425300e+02 -5.592600e+02 +20 4546 -4.763000e+02 -3.145500e+02 +2 4547 4.868101e+02 4.269000e+01 +11 4547 9.699800e+02 1.461800e+02 +17 4547 -1.432890e+03 4.023700e+02 +2 4548 -1.272500e+02 7.101001e+01 +9 4548 -1.743400e+02 2.111599e+02 +11 4548 4.610601e+02 1.558600e+02 +20 4548 -3.184399e+02 -1.822600e+02 +2 4549 4.326100e+02 7.440997e+01 +11 4549 9.389399e+02 1.829900e+02 +17 4549 -1.541800e+03 4.540300e+02 +2 4550 5.157000e+02 8.087000e+01 +11 4550 9.826200e+02 1.711900e+02 +17 4550 -1.366410e+03 4.595400e+02 +2 4551 -2.788200e+02 1.801400e+02 +11 4551 3.338101e+02 2.117300e+02 +2 4552 -2.788200e+02 1.801400e+02 +9 4552 -3.151600e+02 2.755601e+02 +10 4552 -2.401300e+02 -3.413000e+02 +11 4552 3.338101e+02 2.117300e+02 +12 4552 -8.635700e+02 -4.488101e+02 +2 4553 -4.573600e+02 2.700500e+02 +9 4553 -4.572800e+02 3.387800e+02 +10 4553 -3.411100e+02 -2.954301e+02 +11 4553 2.004800e+02 2.722000e+02 +12 4553 -9.769200e+02 -3.995000e+02 +18 4553 -5.580200e+02 9.632007e+01 +20 4553 -4.743500e+02 -1.169900e+02 +2 4554 -5.604500e+02 2.718900e+02 +9 4554 -5.356000e+02 3.394700e+02 +10 4554 -3.966300e+02 -2.943700e+02 +2 4555 -5.604500e+02 2.718900e+02 +9 4555 -5.356000e+02 3.394700e+02 +10 4555 -3.966300e+02 -2.943700e+02 +20 4555 -5.166400e+02 -1.145000e+02 +2 4556 -4.954200e+02 3.068000e+02 +10 4556 -3.625900e+02 -2.753500e+02 +2 4557 -6.751300e+02 3.246000e+02 +9 4557 -6.228900e+02 3.776500e+02 +10 4557 -4.576200e+02 -2.677800e+02 +18 4557 -6.600100e+02 1.230701e+02 +2 4558 7.096300e+02 4.353500e+02 +7 4558 9.761001e+02 5.679200e+02 +12 4558 -1.704000e+02 -2.709399e+02 +17 4558 -1.079060e+03 9.956399e+02 +18 4558 5.125000e+01 1.962700e+02 +2 4559 6.133300e+02 -3.590900e+02 +11 4559 7.805100e+02 -2.466100e+02 +2 4560 -6.540600e+02 -2.185800e+02 +9 4560 -6.028600e+02 -3.191003e+01 +2 4561 -5.215000e+02 -2.171800e+02 +9 4561 -5.018300e+02 -3.014001e+01 +2 4562 -5.215000e+02 -2.171800e+02 +9 4562 -5.018300e+02 -3.014001e+01 +2 4563 4.737500e+02 -2.108200e+02 +9 4563 -4.813000e+01 -1.159000e+02 +2 4564 4.598700e+02 -1.914100e+02 +11 4564 6.810000e+02 -1.522600e+02 +13 4564 -1.271040e+03 -6.493994e+01 +2 4565 -4.456400e+02 -1.908700e+02 +9 4565 -4.460699e+02 -9.920044e+00 +20 4565 -4.741100e+02 -3.037700e+02 +2 4566 -3.638000e+02 -7.306000e+01 +10 4566 -2.898800e+02 -4.812800e+02 +12 4566 -9.253400e+02 -6.053800e+02 +2 4567 -2.712100e+02 -3.178003e+01 +9 4567 -3.079600e+02 1.151500e+02 +10 4567 -2.337200e+02 -4.578600e+02 +11 4567 3.404500e+02 5.627002e+01 +12 4567 -8.603300e+02 -5.781100e+02 +18 4567 -4.670300e+02 -4.506006e+01 +20 4567 -3.957900e+02 -2.371000e+02 +2 4568 -4.903500e+02 1.282001e+01 +9 4568 -4.791400e+02 1.432400e+02 +10 4568 -3.607300e+02 -4.340100e+02 +11 4568 1.783101e+02 8.332001e+01 +16 4568 3.195601e+02 3.035200e+02 +2 4569 5.115200e+02 4.559003e+01 +11 4569 9.814500e+02 1.449900e+02 +2 4570 5.115200e+02 4.559003e+01 +11 4570 9.814500e+02 1.449900e+02 +17 4570 -1.377580e+03 4.055801e+02 +2 4571 -4.146800e+02 5.317999e+01 +9 4571 -4.244900e+02 1.733900e+02 +10 4571 -3.154700e+02 -4.129000e+02 +11 4571 2.351600e+02 1.140300e+02 +12 4571 -9.500400e+02 -5.295699e+02 +2 4572 -3.377300e+02 8.322998e+01 +9 4572 -3.614399e+02 2.005000e+02 +11 4572 2.893300e+02 1.377200e+02 +2 4573 -4.501000e+02 1.162900e+02 +10 4573 -3.373600e+02 -3.788800e+02 +11 4573 2.061700e+02 1.596500e+02 +12 4573 -9.759300e+02 -4.906899e+02 +16 4573 3.399200e+02 3.513000e+02 +20 4573 -4.726000e+02 -1.778300e+02 +2 4574 -4.508600e+02 1.381600e+02 +10 4574 -3.380300e+02 -3.681000e+02 +18 4574 -5.555100e+02 3.368994e+01 +2 4575 -2.666300e+02 1.965200e+02 +11 4575 3.428400e+02 2.256400e+02 +18 4575 -4.632300e+02 6.378003e+01 +2 4576 -1.865900e+02 2.118500e+02 +11 4576 4.071801e+02 2.483800e+02 +2 4577 -3.856500e+02 2.146400e+02 +9 4577 -4.022800e+02 2.982400e+02 +11 4577 2.533700e+02 2.319200e+02 +2 4578 -4.981200e+02 2.804800e+02 +11 4578 1.707100e+02 2.778200e+02 +2 4579 -3.429400e+02 3.289300e+02 +10 4579 -2.766801e+02 -2.620500e+02 +11 4579 2.841700e+02 3.193200e+02 +12 4579 -9.022600e+02 -3.608500e+02 +2 4580 -7.006700e+02 4.023400e+02 +9 4580 -6.441800e+02 4.373700e+02 +11 4580 2.354004e+01 3.641899e+02 +14 4580 4.508400e+02 3.297300e+02 +2 4581 -6.466500e+02 4.091100e+02 +9 4581 -6.021500e+02 4.428500e+02 +2 4582 -3.025300e+02 4.142200e+02 +9 4582 -3.369301e+02 4.561000e+02 +2 4583 -5.221300e+02 4.282500e+02 +9 4583 -5.077700e+02 4.591300e+02 +2 4584 -5.991200e+02 4.299200e+02 +9 4584 -5.673600e+02 4.595200e+02 +2 4585 -4.584700e+02 4.413600e+02 +9 4585 -4.601600e+02 4.705601e+02 +10 4585 -3.415100e+02 -2.030300e+02 +11 4585 1.984000e+02 3.962700e+02 +12 4585 -9.739600e+02 -2.956700e+02 +18 4585 -5.579000e+02 1.784700e+02 +20 4585 -4.738300e+02 -4.554004e+01 +2 4586 -4.710900e+02 4.767700e+02 +10 4586 -3.477900e+02 -1.840000e+02 +2 4587 -3.900700e+02 -2.023400e+02 +9 4587 -4.019399e+02 -1.776001e+01 +2 4588 -3.900700e+02 -2.023400e+02 +10 4588 -3.047000e+02 -5.513000e+02 +20 4588 -4.496400e+02 -3.085000e+02 +2 4589 -4.339500e+02 -2.023900e+02 +10 4589 -3.285300e+02 -5.513500e+02 +11 4589 2.206300e+02 -7.166998e+01 +20 4589 -4.673600e+02 -3.086100e+02 +2 4590 -4.566600e+02 -2.025200e+02 +9 4590 -4.544399e+02 -1.918994e+01 +20 4590 -4.794600e+02 -3.087400e+02 +2 4591 -4.566600e+02 -2.025200e+02 +9 4591 -4.544399e+02 -1.918994e+01 +20 4591 -4.794600e+02 -3.087400e+02 +2 4592 -4.333800e+02 -1.259400e+02 +9 4592 -4.362300e+02 3.926001e+01 +2 4593 -3.927800e+02 -9.908002e+01 +9 4593 -4.045200e+02 6.047998e+01 +12 4593 -9.444900e+02 -6.210800e+02 +2 4594 -3.927800e+02 -9.908002e+01 +9 4594 -4.045200e+02 6.047998e+01 +2 4595 -3.147100e+02 -8.700000e+01 +10 4595 -2.607600e+02 -4.882200e+02 +2 4596 -2.886800e+02 -8.534998e+01 +10 4596 -2.453500e+02 -4.880900e+02 +11 4596 3.261801e+02 1.542999e+01 +2 4597 -4.660200e+02 -7.363000e+01 +10 4597 -3.467500e+02 -4.814900e+02 +11 4597 1.958000e+02 2.104999e+01 +12 4597 -9.906900e+02 -6.059500e+02 +18 4597 -5.645200e+02 -6.605005e+01 +2 4598 -5.731600e+02 -2.278998e+01 +9 4598 -5.411600e+02 1.154399e+02 +2 4599 -3.981500e+02 -4.150024e+00 +9 4599 -4.093400e+02 1.328000e+02 +11 4599 2.452700e+02 7.244000e+01 +18 4599 -5.307400e+02 -3.242004e+01 +2 4600 -1.938100e+02 1.910999e+01 +9 4600 -2.409500e+02 1.619900e+02 +11 4600 4.013700e+02 1.015200e+02 +2 4601 -1.921100e+02 3.534998e+01 +11 4601 4.033199e+02 1.141600e+02 +2 4602 4.216801e+02 5.891998e+01 +11 4602 9.285300e+02 1.696800e+02 +17 4602 -1.553940e+03 4.302800e+02 +2 4603 -2.490400e+02 6.304999e+01 +9 4603 -2.881000e+02 1.905300e+02 +10 4603 -2.178600e+02 -4.059000e+02 +11 4603 3.570200e+02 1.284300e+02 +20 4603 -3.842900e+02 -1.970900e+02 +2 4604 -4.192500e+02 1.037100e+02 +9 4604 -4.265000e+02 2.133101e+02 +10 4604 -3.205100e+02 -3.844600e+02 +11 4604 2.296600e+02 1.502600e+02 +12 4604 -9.567500e+02 -4.976100e+02 +2 4605 -4.094800e+02 1.137500e+02 +11 4605 2.359700e+02 1.579600e+02 +2 4606 -2.920800e+02 1.488400e+02 +11 4606 3.235400e+02 1.884200e+02 +12 4606 -8.710300e+02 -4.689100e+02 +18 4606 -4.768101e+02 4.114001e+01 +2 4607 4.808199e+02 2.017200e+02 +11 4607 9.676700e+02 2.770100e+02 +2 4608 4.920500e+02 2.591100e+02 +11 4608 9.771899e+02 3.254300e+02 +2 4609 -6.872200e+02 2.589700e+02 +9 4609 -6.311500e+02 3.272500e+02 +2 4610 -2.809600e+02 2.675900e+02 +10 4610 -2.401300e+02 -2.950200e+02 +11 4610 3.309500e+02 2.779700e+02 +12 4610 -8.607300e+02 -3.980100e+02 +18 4610 -4.708900e+02 9.773999e+01 +2 4611 -3.782400e+02 2.984200e+02 +10 4611 -2.974800e+02 -2.793500e+02 +2 4612 -4.908900e+02 3.194500e+02 +9 4612 -4.828500e+02 3.750200e+02 +11 4612 1.761899e+02 3.059900e+02 +2 4613 -2.755200e+02 3.549100e+02 +9 4613 -3.145200e+02 4.093201e+02 +11 4613 3.356899e+02 3.414700e+02 +2 4614 7.420100e+02 3.597400e+02 +7 4614 9.988401e+02 5.189299e+02 +17 4614 -1.026100e+03 8.763101e+02 +2 4615 7.725300e+02 3.640700e+02 +7 4615 1.018820e+03 5.238201e+02 +9 4615 5.618301e+02 4.705000e+02 +12 4615 -1.332000e+02 -3.152100e+02 +17 4615 -9.805100e+02 8.819900e+02 +20 4615 7.522998e+01 -5.603003e+01 +2 4616 7.502600e+02 3.707500e+02 +7 4616 1.003960e+03 5.276599e+02 +12 4616 -1.464900e+02 -3.157200e+02 +2 4617 7.502600e+02 3.707500e+02 +7 4617 1.003960e+03 5.276599e+02 +9 4617 5.448101e+02 4.717000e+02 +20 4617 6.568994e+01 -5.370996e+01 +2 4618 -3.714500e+02 3.704100e+02 +11 4618 2.635200e+02 3.468800e+02 +12 4618 -9.202400e+02 -3.385900e+02 +18 4618 -5.158900e+02 1.445100e+02 +20 4618 -4.373400e+02 -7.396997e+01 +2 4619 -2.895100e+02 3.886200e+02 +9 4619 -3.277000e+02 4.363500e+02 +10 4619 -2.444100e+02 -2.298300e+02 +11 4619 3.246801e+02 3.676899e+02 +18 4619 -4.740601e+02 1.554399e+02 +20 4619 -4.018500e+02 -6.448999e+01 +2 4620 -4.487600e+02 3.953400e+02 +9 4620 -4.527100e+02 4.346599e+02 +10 4620 -3.358700e+02 -2.280000e+02 +11 4620 2.055200e+02 3.625200e+02 +12 4620 -9.688100e+02 -3.237300e+02 +18 4620 -5.535800e+02 1.560801e+02 +2 4621 -4.487600e+02 3.953400e+02 +9 4621 -4.527100e+02 4.346599e+02 +10 4621 -3.358700e+02 -2.280000e+02 +11 4621 2.055200e+02 3.625200e+02 +12 4621 -9.688100e+02 -3.237300e+02 +18 4621 -5.535800e+02 1.560801e+02 +2 4622 -4.377900e+02 4.038200e+02 +9 4622 -4.439800e+02 4.411599e+02 +10 4622 -3.299800e+02 -2.228300e+02 +12 4622 -9.614900e+02 -3.180500e+02 +18 4622 -5.480400e+02 1.605300e+02 +20 4622 -4.653101e+02 -6.064001e+01 +2 4623 -3.967000e+02 4.077400e+02 +9 4623 -4.123600e+02 4.456100e+02 +10 4623 -3.069200e+02 -2.205100e+02 +11 4623 2.440200e+02 3.737900e+02 +2 4624 -4.568900e+02 4.177400e+02 +9 4624 -4.594100e+02 4.521100e+02 +11 4624 1.993900e+02 3.793600e+02 +12 4624 -9.742600e+02 -3.095699e+02 +18 4624 -5.576800e+02 1.665500e+02 +20 4624 -4.735000e+02 -5.495996e+01 +2 4625 -4.568900e+02 4.177400e+02 +9 4625 -4.594100e+02 4.521100e+02 +10 4625 -3.408300e+02 -2.155200e+02 +11 4625 1.993900e+02 3.793600e+02 +18 4625 -5.576800e+02 1.665500e+02 +2 4626 -2.738100e+02 4.224400e+02 +9 4626 -3.126400e+02 4.649099e+02 +11 4626 3.367000e+02 3.945800e+02 +2 4627 -7.436200e+02 4.230500e+02 +9 4627 -6.750800e+02 4.532300e+02 +11 4627 -6.349976e+00 3.792500e+02 +14 4627 4.358900e+02 3.364000e+02 +2 4628 -3.683800e+02 4.366100e+02 +9 4628 -3.898500e+02 4.708600e+02 +2 4629 -4.373600e+02 4.418201e+02 +9 4629 -4.440601e+02 4.710100e+02 +11 4629 2.141899e+02 3.976100e+02 +18 4629 -5.475100e+02 1.786000e+02 +20 4629 -4.647400e+02 -4.500000e+01 +2 4630 -7.203700e+02 4.466100e+02 +10 4630 -4.792500e+02 -2.017100e+02 +12 4630 -1.130870e+03 -2.903800e+02 +2 4631 -2.824300e+02 4.561400e+02 +9 4631 -3.185800e+02 4.980500e+02 +11 4631 3.318800e+02 4.238201e+02 +2 4632 -4.276500e+02 4.585100e+02 +9 4632 -4.370601e+02 4.850300e+02 +10 4632 -3.237200e+02 -1.942700e+02 +11 4632 2.209200e+02 4.112100e+02 +12 4632 -9.543200e+02 -2.863700e+02 +18 4632 -5.426400e+02 1.864700e+02 +20 4632 -4.605500e+02 -3.796997e+01 +2 4633 -4.451100e+02 4.773900e+02 +9 4633 -4.505601e+02 4.975701e+02 +10 4633 -3.345900e+02 -1.835400e+02 +2 4634 6.508600e+02 -3.747000e+02 +11 4634 8.040200e+02 -2.552500e+02 +2 4635 6.362800e+02 -3.742400e+02 +11 4635 7.948101e+02 -2.540900e+02 +20 4635 -2.238300e+02 -4.158800e+02 +2 4636 5.219600e+02 -3.054300e+02 +11 4636 7.187900e+02 -2.169000e+02 +2 4637 4.663101e+02 -2.035600e+02 +11 4637 6.851899e+02 -1.597300e+02 +2 4638 4.663101e+02 -2.035600e+02 +11 4638 6.851899e+02 -1.597300e+02 +2 4639 -3.355600e+02 -2.016900e+02 +11 4639 2.918000e+02 -6.982001e+01 +2 4640 -2.702800e+02 -1.999200e+02 +10 4640 -2.332900e+02 -5.496600e+02 +11 4640 3.414700e+02 -6.665997e+01 +2 4641 4.484500e+02 -1.951300e+02 +11 4641 6.754900e+02 -1.550300e+02 +2 4642 -2.780900e+02 -1.929200e+02 +11 4642 3.348600e+02 -6.165002e+01 +2 4643 -2.780900e+02 -1.929200e+02 +11 4643 3.348600e+02 -6.165002e+01 +2 4644 4.448800e+02 -1.812500e+02 +9 4644 -6.346997e+01 -9.858997e+01 +2 4645 -2.901100e+02 -1.766400e+02 +11 4645 3.258101e+02 -5.029999e+01 +2 4646 4.461801e+02 -1.716200e+02 +9 4646 -6.243005e+01 -9.255005e+01 +11 4646 6.735500e+02 -1.406200e+02 +2 4647 -3.292400e+02 -1.721100e+02 +9 4647 -3.548500e+02 6.300049e+00 +11 4647 2.964500e+02 -4.921002e+01 +18 4647 -4.990400e+02 -1.123000e+02 +20 4647 -4.236400e+02 -2.952700e+02 +2 4648 -2.594100e+02 -1.686500e+02 +9 4648 -2.973900e+02 1.243005e+01 +10 4648 -2.251899e+02 -5.318300e+02 +11 4648 3.499900e+02 -4.351001e+01 +18 4648 -4.620100e+02 -1.094900e+02 +20 4648 -3.919000e+02 -2.929900e+02 +2 4649 -4.590700e+02 -1.649400e+02 +9 4649 -4.548900e+02 1.047998e+01 +2 4650 -3.597700e+02 -1.589400e+02 +11 4650 2.737700e+02 -3.928003e+01 +12 4650 -9.249800e+02 -6.565699e+02 +20 4650 -4.363300e+02 -2.901400e+02 +2 4651 7.757200e+02 -1.535300e+02 +3 4651 1.092010e+03 -1.785500e+02 +5 4651 1.213630e+03 6.470500e+02 +2 4652 -4.596000e+02 -8.681000e+01 +10 4652 -3.437600e+02 -4.890800e+02 +11 4652 2.005800e+02 1.165002e+01 +12 4652 -9.871800e+02 -6.154900e+02 +2 4653 -2.729200e+02 -7.715997e+01 +11 4653 3.386100e+02 2.292999e+01 +18 4653 -4.691000e+02 -6.623999e+01 +2 4654 -2.729200e+02 -7.715997e+01 +11 4654 3.386100e+02 2.292999e+01 +2 4655 -3.281700e+02 -7.257001e+01 +11 4655 2.961100e+02 2.513000e+01 +18 4655 -4.973800e+02 -6.500000e+01 +2 4656 -4.223100e+02 -7.078003e+01 +9 4656 -4.277900e+02 8.140002e+01 +2 4657 4.425500e+02 -6.431000e+01 +11 4657 9.377700e+02 6.409998e+01 +2 4658 5.050200e+02 -6.001001e+01 +11 4658 9.790200e+02 6.187000e+01 +17 4658 -1.391900e+03 2.419099e+02 +2 4659 -2.149300e+02 2.238000e+01 +11 4659 3.848700e+02 1.031400e+02 +13 4659 -1.558740e+03 3.243800e+02 +18 4659 -4.342100e+02 -1.534998e+01 +20 4659 -3.673600e+02 -2.113300e+02 +2 4660 -2.897700e+02 3.035999e+01 +11 4660 3.250900e+02 1.003500e+02 +12 4660 -8.718800e+02 -5.403500e+02 +2 4661 -1.480100e+02 3.366998e+01 +11 4661 4.401200e+02 1.191500e+02 +2 4662 -3.089100e+02 7.170001e+01 +9 4662 -3.418101e+02 1.924299e+02 +11 4662 3.107300e+02 1.305600e+02 +12 4662 -8.852400e+02 -5.159900e+02 +18 4662 -4.855900e+02 3.680054e+00 +2 4663 -3.949600e+02 8.340002e+01 +11 4663 2.453101e+02 1.375200e+02 +2 4664 -3.196800e+02 8.913000e+01 +10 4664 -2.642300e+02 -3.925900e+02 +11 4664 3.021000e+02 1.428300e+02 +12 4664 -8.930700e+02 -5.063600e+02 +18 4664 -4.915800e+02 1.168994e+01 +20 4664 -4.166000e+02 -1.879301e+02 +2 4665 -2.533000e+02 9.681000e+01 +9 4665 -2.939200e+02 2.159900e+02 +11 4665 3.538400e+02 1.528000e+02 +2 4666 -2.100700e+02 1.137400e+02 +10 4666 -1.898000e+02 -3.771899e+02 +11 4666 3.883300e+02 1.716700e+02 +12 4666 -8.035300e+02 -4.839000e+02 +13 4666 -1.536050e+03 5.511400e+02 +18 4666 -4.299800e+02 2.933997e+01 +20 4666 -3.644200e+02 -1.727600e+02 +2 4667 -2.100700e+02 1.137400e+02 +11 4667 3.883300e+02 1.716700e+02 +2 4668 -1.941000e+02 1.310300e+02 +11 4668 4.023199e+02 1.865500e+02 +2 4669 -3.980800e+02 1.603200e+02 +10 4669 -3.081500e+02 -3.542600e+02 +2 4670 -3.980800e+02 1.603200e+02 +10 4670 -3.081500e+02 -3.542600e+02 +2 4671 -2.160200e+02 2.155500e+02 +9 4671 -2.608101e+02 3.141599e+02 +10 4671 -1.945300e+02 -3.216100e+02 +13 4671 -1.555190e+03 8.066300e+02 +20 4671 -3.668600e+02 -1.310400e+02 +2 4672 -1.968400e+02 2.261600e+02 +9 4672 -2.451400e+02 3.231699e+02 +11 4672 3.974500e+02 2.569000e+02 +2 4673 -4.822600e+02 2.541300e+02 +11 4673 1.824800e+02 2.577500e+02 +12 4673 -9.943200e+02 -4.083101e+02 +18 4673 -5.707000e+02 8.872998e+01 +2 4674 -4.017800e+02 2.546200e+02 +11 4674 2.411500e+02 2.604900e+02 +18 4674 -5.315300e+02 8.903003e+01 +20 4674 -4.511300e+02 -1.214100e+02 +2 4675 -4.422200e+02 2.566100e+02 +9 4675 -4.455100e+02 3.285901e+02 +10 4675 -3.329399e+02 -3.024800e+02 +11 4675 2.115699e+02 2.611800e+02 +12 4675 -9.678000e+02 -4.069200e+02 +18 4675 -5.510100e+02 9.033008e+01 +20 4675 -4.681700e+02 -1.207000e+02 +2 4676 -4.422200e+02 2.566100e+02 +9 4676 -4.455100e+02 3.285901e+02 +10 4676 -3.329399e+02 -3.024800e+02 +11 4676 2.115699e+02 2.611800e+02 +12 4676 -9.678000e+02 -4.069200e+02 +18 4676 -5.510100e+02 9.033008e+01 +2 4677 -4.703900e+02 2.579800e+02 +10 4677 -3.491700e+02 -3.015699e+02 +11 4677 1.916700e+02 2.608800e+02 +12 4677 -9.863900e+02 -4.061801e+02 +20 4677 -4.794301e+02 -1.208101e+02 +2 4678 -4.961100e+02 2.576900e+02 +9 4678 -4.848300e+02 3.261599e+02 +11 4678 1.739600e+02 2.585400e+02 +16 4678 3.168000e+02 4.137500e+02 +2 4679 -4.018400e+02 2.653500e+02 +9 4679 -4.143000e+02 3.373201e+02 +10 4679 -3.102200e+02 -2.970400e+02 +11 4679 2.411600e+02 2.695100e+02 +20 4679 -4.510000e+02 -1.167700e+02 +2 4680 -4.420900e+02 2.926400e+02 +9 4680 -4.455500e+02 3.568500e+02 +10 4680 -3.325601e+02 -2.829399e+02 +11 4680 2.115000e+02 2.879400e+02 +12 4680 -9.669500e+02 -3.845601e+02 +2 4681 -4.420900e+02 2.926400e+02 +9 4681 -4.455500e+02 3.568500e+02 +10 4681 -3.325601e+02 -2.829399e+02 +12 4681 -9.669500e+02 -3.845601e+02 +2 4682 -3.786100e+02 3.158200e+02 +9 4682 -3.969000e+02 3.762500e+02 +11 4682 2.583900e+02 3.065000e+02 +18 4682 -5.197300e+02 1.189099e+02 +2 4683 -3.786100e+02 3.158200e+02 +9 4683 -3.969000e+02 3.762500e+02 +18 4683 -5.197300e+02 1.189099e+02 +20 4683 -4.410500e+02 -9.521997e+01 +2 4684 7.509500e+02 3.441800e+02 +9 4684 5.459299e+02 4.483301e+02 +12 4684 -1.462700e+02 -3.307200e+02 +2 4685 -4.229900e+02 3.436800e+02 +10 4685 -3.219700e+02 -2.559000e+02 +11 4685 2.252200e+02 3.262400e+02 +2 4686 7.503500e+02 3.531500e+02 +7 4686 1.003630e+03 5.151699e+02 +9 4686 5.448701e+02 4.578101e+02 +12 4686 -1.465900e+02 -3.232900e+02 +2 4687 7.034399e+02 3.529300e+02 +9 4687 5.069301e+02 4.577000e+02 +12 4687 -1.753300e+02 -3.232700e+02 +17 4687 -1.086790e+03 8.696899e+02 +2 4688 -1.844100e+02 3.614800e+02 +9 4688 -1.831899e+02 4.902300e+02 +2 4689 -3.626000e+02 3.655300e+02 +11 4689 2.692300e+02 3.430500e+02 +2 4690 -4.663800e+02 3.817000e+02 +11 4690 1.932400e+02 3.523400e+02 +2 4691 -4.564900e+02 3.867800e+02 +11 4691 2.007500e+02 3.557400e+02 +18 4691 -5.569300e+02 1.514500e+02 +2 4692 -3.518200e+02 3.945500e+02 +11 4692 2.777400e+02 3.665701e+02 +18 4692 -5.058700e+02 1.567000e+02 +20 4692 -4.285699e+02 -6.355005e+01 +2 4693 -4.580400e+02 4.045300e+02 +9 4693 -4.590800e+02 4.419199e+02 +10 4693 -3.415000e+02 -2.228000e+02 +11 4693 1.994200e+02 3.698600e+02 +12 4693 -9.745300e+02 -3.180100e+02 +18 4693 -5.579400e+02 1.603900e+02 +20 4693 -4.735200e+02 -6.005005e+01 +2 4694 -6.323700e+02 4.121800e+02 +11 4694 7.326001e+01 3.719800e+02 +16 4694 2.556500e+02 4.810601e+02 +18 4694 -6.408000e+02 1.641500e+02 +2 4695 -4.469000e+02 4.231300e+02 +10 4695 -3.348199e+02 -2.122200e+02 +11 4695 2.068199e+02 3.839000e+02 +12 4695 -9.673200e+02 -3.070000e+02 +18 4695 -5.521600e+02 1.689299e+02 +2 4696 -5.507300e+02 4.255400e+02 +10 4696 -3.901300e+02 -2.124900e+02 +2 4697 -7.421000e+02 4.319900e+02 +11 4697 -4.979980e+00 3.865400e+02 +2 4698 6.020800e+02 -2.870800e+02 +11 4698 7.750400e+02 -2.052800e+02 +2 4699 -6.836500e+02 -2.699400e+02 +9 4699 -6.223900e+02 -7.080005e+01 +2 4700 -6.836500e+02 -2.699400e+02 +9 4700 -6.223900e+02 -7.080005e+01 +2 4701 -7.297300e+02 -2.702500e+02 +9 4701 -6.575700e+02 -7.109998e+01 +2 4702 -1.603500e+02 -1.969900e+02 +11 4702 4.302000e+02 -5.771002e+01 +20 4702 -3.414200e+02 -3.013700e+02 +2 4703 -1.603500e+02 -1.969900e+02 +11 4703 4.302000e+02 -5.771002e+01 +2 4704 -1.634500e+02 -1.901400e+02 +11 4704 4.271801e+02 -5.260999e+01 +2 4705 -2.551700e+02 -1.833900e+02 +11 4705 3.532500e+02 -5.370001e+01 +2 4706 -2.650700e+02 -1.827100e+02 +10 4706 -2.297300e+02 -5.407300e+02 +11 4706 3.450300e+02 -5.415002e+01 +12 4706 -8.578200e+02 -6.702000e+02 +18 4706 -4.656200e+02 -1.167800e+02 +2 4707 -3.216700e+02 -1.789300e+02 +11 4707 3.022100e+02 -5.298999e+01 +12 4707 -8.993300e+02 -6.685601e+02 +2 4708 -3.216700e+02 -1.789300e+02 +10 4708 -2.652000e+02 -5.383500e+02 +11 4708 3.022100e+02 -5.298999e+01 +12 4708 -8.993300e+02 -6.685601e+02 +20 4708 -4.200601e+02 -2.982400e+02 +2 4709 4.585601e+02 -1.683300e+02 +9 4709 -5.681995e+01 -9.106995e+01 +11 4709 6.811200e+02 -1.394100e+02 +2 4710 -1.599400e+02 -1.505700e+02 +11 4710 4.302500e+02 -2.203998e+01 +2 4711 -2.801200e+02 -9.387000e+01 +10 4711 -2.400699e+02 -4.917000e+02 +11 4711 3.330000e+02 1.045001e+01 +2 4712 -2.360800e+02 -9.137000e+01 +9 4712 -2.773500e+02 7.259998e+01 +11 4712 3.677000e+02 1.562000e+01 +13 4712 -1.635140e+03 4.323999e+01 +2 4713 -2.727200e+02 -8.846997e+01 +10 4713 -2.353800e+02 -4.889600e+02 +11 4713 3.385200e+02 1.484003e+01 +12 4713 -8.625700e+02 -6.126801e+02 +2 4714 -2.363700e+02 -8.012000e+01 +10 4714 -2.096000e+02 -4.838500e+02 +11 4714 3.674399e+02 2.367999e+01 +2 4715 -2.648000e+02 -7.441998e+01 +10 4715 -2.294100e+02 -4.812700e+02 +11 4715 3.450200e+02 2.560999e+01 +12 4715 -8.551000e+02 -6.037900e+02 +20 4715 -3.934301e+02 -2.543600e+02 +2 4716 -2.630500e+02 -6.673999e+01 +11 4716 3.463000e+02 3.158002e+01 +2 4717 5.231000e+02 -4.978998e+01 +11 4717 9.870699e+02 6.657001e+01 +17 4717 -1.354030e+03 2.572600e+02 +2 4718 5.362400e+02 -4.607001e+01 +11 4718 9.947200e+02 6.678998e+01 +2 4719 5.292300e+02 -4.740997e+01 +11 4719 9.905500e+02 6.766998e+01 +2 4720 5.431500e+02 -4.415002e+01 +11 4720 9.983700e+02 6.889001e+01 +17 4720 -1.314720e+03 2.658700e+02 +2 4721 -2.099700e+02 -3.860999e+01 +9 4721 -2.547900e+02 1.159000e+02 +11 4721 3.886300e+02 5.695001e+01 +13 4721 -1.550720e+03 1.713500e+02 +18 4721 -4.324900e+02 -4.516003e+01 +20 4721 -3.660000e+02 -2.368700e+02 +2 4722 -3.233800e+02 -3.309998e+01 +9 4722 -3.507100e+02 1.119399e+02 +10 4722 -2.659800e+02 -4.587900e+02 +11 4722 3.005100e+02 5.321002e+01 +12 4722 -8.969100e+02 -5.800000e+02 +18 4722 -4.944900e+02 -4.639001e+01 +20 4722 -4.195200e+02 -2.384301e+02 +2 4723 -5.398100e+02 -2.583002e+01 +9 4723 -5.163300e+02 1.117300e+02 +10 4723 -3.876801e+02 -4.548600e+02 +11 4723 1.432600e+02 5.301001e+01 +16 4723 2.974700e+02 2.866600e+02 +2 4724 -2.317900e+02 -2.138000e+01 +9 4724 -2.739500e+02 1.278201e+02 +11 4724 3.710200e+02 6.775000e+01 +18 4724 -4.448199e+02 -3.766003e+01 +20 4724 -3.766899e+02 -2.309700e+02 +2 4725 -5.832400e+02 -2.113000e+01 +9 4725 -5.502000e+02 1.164399e+02 +20 4725 -5.284500e+02 -2.345500e+02 +2 4726 -2.071600e+02 -6.929993e+00 +9 4726 -2.525699e+02 1.402000e+02 +11 4726 3.907600e+02 8.046002e+01 +13 4726 -1.541760e+03 2.509199e+02 +18 4726 -4.307700e+02 -2.959998e+01 +2 4727 -3.359500e+02 -1.280029e+00 +11 4727 2.907400e+02 7.613000e+01 +2 4728 -4.868100e+02 3.929993e+00 +11 4728 1.800100e+02 7.654999e+01 +2 4729 -2.198900e+02 1.354999e+01 +9 4729 -2.624301e+02 1.564500e+02 +2 4730 -4.624700e+02 2.546002e+01 +11 4730 1.980699e+02 9.304999e+01 +2 4731 -2.398200e+02 5.884998e+01 +9 4731 -2.807700e+02 1.874900e+02 +11 4731 3.645500e+02 1.259100e+02 +13 4731 -1.636190e+03 4.142500e+02 +2 4732 3.835400e+02 7.201001e+01 +11 4732 9.039100e+02 1.833500e+02 +2 4733 -2.853800e+02 7.367999e+01 +10 4733 -2.421000e+02 -3.998600e+02 +11 4733 3.292500e+02 1.326000e+02 +2 4734 3.799100e+02 1.070000e+02 +11 4734 9.025699e+02 2.143700e+02 +2 4735 4.317900e+02 1.088900e+02 +11 4735 9.474000e+02 2.172400e+02 +2 4736 -4.999200e+02 1.490400e+02 +11 4736 1.704399e+02 1.809200e+02 +2 4737 -2.405700e+02 1.502400e+02 +9 4737 -2.819100e+02 2.586500e+02 +11 4737 3.638199e+02 1.946400e+02 +12 4737 -8.286300e+02 -4.653000e+02 +13 4737 -1.633150e+03 6.409900e+02 +2 4738 -2.405700e+02 1.502400e+02 +9 4738 -2.819100e+02 2.586500e+02 +11 4738 3.638199e+02 1.946400e+02 +12 4738 -8.286300e+02 -4.653000e+02 +13 4738 -1.633150e+03 6.409900e+02 +2 4739 -3.714700e+02 1.507200e+02 +10 4739 -2.936899e+02 -3.593900e+02 +11 4739 2.637100e+02 1.865700e+02 +2 4740 -1.246000e+02 1.636100e+02 +11 4740 4.624000e+02 2.234100e+02 +2 4741 -2.295800e+02 1.729200e+02 +9 4741 -2.736100e+02 2.776799e+02 +10 4741 -2.044800e+02 -3.457100e+02 +12 4741 -8.205200e+02 -4.498600e+02 +13 4741 -1.599610e+03 6.995000e+02 +18 4741 -4.417200e+02 5.620996e+01 +20 4741 -3.742900e+02 -1.497700e+02 +2 4742 -1.801300e+02 2.129900e+02 +9 4742 -2.282500e+02 3.151500e+02 +11 4742 4.115800e+02 2.496300e+02 +13 4742 -1.440530e+03 7.948800e+02 +2 4743 -2.282100e+02 2.139800e+02 +10 4743 -2.045500e+02 -3.231200e+02 +11 4743 3.720100e+02 2.427800e+02 +13 4743 -1.601090e+03 8.029100e+02 +18 4743 -4.430200e+02 7.469995e+01 +20 4743 -3.748000e+02 -1.334900e+02 +2 4744 -4.899700e+02 2.160600e+02 +9 4744 -4.812900e+02 2.966799e+02 +11 4744 1.772300e+02 2.302500e+02 +2 4745 -4.829800e+02 2.218100e+02 +11 4745 1.822900e+02 2.349200e+02 +2 4746 -2.995500e+02 2.246500e+02 +11 4746 3.173900e+02 2.435600e+02 +2 4747 4.898500e+02 2.369200e+02 +11 4747 9.684700e+02 3.007100e+02 +2 4748 -5.161400e+02 2.511600e+02 +11 4748 1.574900e+02 2.554600e+02 +16 4748 3.050400e+02 4.108700e+02 +2 4749 -3.755200e+02 2.521000e+02 +9 4749 -3.944100e+02 3.264600e+02 +10 4749 -2.956300e+02 -3.041000e+02 +11 4749 2.602500e+02 2.596600e+02 +18 4749 -5.187900e+02 8.856006e+01 +20 4749 -4.398400e+02 -1.219700e+02 +2 4750 -3.872200e+02 2.535900e+02 +9 4750 -4.022600e+02 3.275601e+02 +11 4750 2.517900e+02 2.633000e+02 +18 4750 -5.239700e+02 8.991992e+01 +2 4751 -3.811100e+02 2.587700e+02 +11 4751 2.562700e+02 2.640700e+02 +18 4751 -5.212600e+02 9.085999e+01 +2 4752 -2.037600e+02 2.919500e+02 +10 4752 -1.627900e+02 -2.774900e+02 +12 4752 -7.582500e+02 -3.603199e+02 +13 4752 -1.413320e+03 9.888899e+02 +18 4752 -4.097700e+02 1.270901e+02 +2 4753 -3.951200e+02 2.959900e+02 +11 4753 2.462600e+02 2.921000e+02 +18 4753 -5.277700e+02 1.090701e+02 +2 4754 -4.409700e+02 3.088300e+02 +11 4754 2.124000e+02 2.997600e+02 +2 4755 -3.302700e+02 3.265400e+02 +10 4755 -2.692600e+02 -2.640601e+02 +11 4755 2.939900e+02 3.174500e+02 +2 4756 -2.660700e+02 3.446700e+02 +10 4756 -2.303400e+02 -2.524800e+02 +18 4756 -4.617600e+02 1.356799e+02 +2 4757 -2.850100e+02 3.498500e+02 +10 4757 -2.426200e+02 -2.502200e+02 +11 4757 3.278700e+02 3.367200e+02 +2 4758 -2.850100e+02 3.498500e+02 +10 4758 -2.426200e+02 -2.502200e+02 +11 4758 3.278700e+02 3.367200e+02 +2 4759 -2.971800e+02 3.584500e+02 +9 4759 -3.332700e+02 4.124299e+02 +2 4760 -6.428800e+02 3.603600e+02 +10 4760 -4.405300e+02 -2.473199e+02 +11 4760 6.655005e+01 3.334000e+02 +2 4761 -2.726600e+02 3.802000e+02 +11 4761 3.382100e+02 3.622900e+02 +2 4762 -3.427000e+02 4.047500e+02 +9 4762 -3.698300e+02 4.460000e+02 +10 4762 -2.763199e+02 -2.215900e+02 +12 4762 -9.001200e+02 -3.166100e+02 +18 4762 -5.013700e+02 1.618700e+02 +2 4763 -5.920700e+02 4.110200e+02 +10 4763 -4.135800e+02 -2.197100e+02 +2 4764 -2.867600e+02 4.144500e+02 +11 4764 3.266899e+02 3.864200e+02 +2 4765 7.819600e+02 4.171600e+02 +9 4765 5.744099e+02 5.082700e+02 +10 4765 3.913701e+02 -2.005800e+02 +18 4765 9.110999e+01 1.851000e+02 +20 4765 8.223999e+01 -3.613000e+01 +2 4766 -5.494900e+02 4.249500e+02 +11 4766 1.327900e+02 3.823700e+02 +2 4767 -3.585200e+02 4.321500e+02 +9 4767 -3.823300e+02 4.662500e+02 +2 4768 -5.460000e+02 4.526100e+02 +11 4768 1.348400e+02 4.024600e+02 +2 4769 -4.214300e+02 4.666500e+02 +9 4769 -4.314399e+02 4.897600e+02 +20 4769 -4.585800e+02 -3.497998e+01 +2 4770 -2.973200e+02 4.684700e+02 +10 4770 -2.463000e+02 -1.849700e+02 +2 4771 5.390400e+02 -3.847100e+02 +11 4771 7.303101e+02 -2.611500e+02 +2 4772 -3.364300e+02 -2.078500e+02 +9 4772 -3.602600e+02 -2.060999e+01 +11 4772 2.915601e+02 -7.442999e+01 +2 4773 -3.757000e+02 -2.080000e+02 +10 4773 -3.106300e+02 -5.549000e+02 +11 4773 2.622200e+02 -7.534998e+01 +2 4774 -2.859000e+02 -2.068500e+02 +9 4774 -3.214700e+02 -1.867004e+01 +2 4775 -2.680900e+02 -2.061300e+02 +11 4775 3.423800e+02 -7.154999e+01 +2 4776 -2.780600e+02 -2.058000e+02 +9 4776 -3.131801e+02 -1.747998e+01 +2 4777 -2.350400e+02 -1.991900e+02 +11 4777 3.691300e+02 -6.397998e+01 +2 4778 4.996400e+02 -1.964300e+02 +11 4778 7.058400e+02 -1.552100e+02 +13 4778 -1.174630e+03 -7.859998e+01 +2 4779 -2.704100e+02 -1.894200e+02 +10 4779 -2.339800e+02 -5.439600e+02 +11 4779 3.407600e+02 -5.925000e+01 +12 4779 -8.634100e+02 -6.738101e+02 +2 4780 4.454000e+02 -1.870200e+02 +11 4780 6.735200e+02 -1.499100e+02 +2 4781 -3.281000e+02 -1.837700e+02 +11 4781 2.972000e+02 -5.678998e+01 +12 4781 -9.042700e+02 -6.724700e+02 +2 4782 -2.226800e+02 -1.759800e+02 +9 4782 -2.651200e+02 8.979980e+00 +2 4783 -3.372100e+02 -1.748800e+02 +11 4783 2.907700e+02 -5.058002e+01 +2 4784 -2.797900e+02 -1.685200e+02 +11 4784 3.338101e+02 -4.403998e+01 +2 4785 -2.360700e+02 -1.634600e+02 +9 4785 -2.768400e+02 1.790002e+01 +10 4785 -2.095200e+02 -5.297400e+02 +11 4785 3.679800e+02 -3.742999e+01 +13 4785 -1.638660e+03 -1.359600e+02 +2 4786 -3.418600e+02 -1.591600e+02 +11 4786 2.873900e+02 -3.944000e+01 +2 4787 -2.356900e+02 -1.527700e+02 +9 4787 -2.769900e+02 2.620996e+01 +10 4787 -2.091801e+02 -5.238700e+02 +11 4787 3.682000e+02 -2.978003e+01 +13 4787 -1.636850e+03 -1.097600e+02 +2 4788 -3.235700e+02 -8.550000e+01 +9 4788 -3.505100e+02 7.280005e+01 +11 4788 3.003500e+02 1.501001e+01 +12 4788 -8.985900e+02 -6.119600e+02 +2 4789 -2.801100e+02 -8.309998e+01 +10 4789 -2.400699e+02 -4.860000e+02 +11 4789 3.328800e+02 1.826001e+01 +12 4789 -8.681500e+02 -6.096200e+02 +2 4790 -1.462900e+02 -8.228998e+01 +9 4790 -1.943800e+02 8.937000e+01 +10 4790 -1.432200e+02 -4.843600e+02 +11 4790 4.421300e+02 3.107001e+01 +12 4790 -7.495900e+02 -6.000800e+02 +13 4790 -1.338200e+03 5.356995e+01 +2 4791 -1.332800e+02 -7.792999e+01 +11 4791 4.540800e+02 3.719000e+01 +2 4792 -1.332800e+02 -7.792999e+01 +11 4792 4.540800e+02 3.719000e+01 +2 4793 -2.549600e+02 -7.347998e+01 +9 4793 -2.938700e+02 8.517004e+01 +11 4793 3.531801e+02 2.734003e+01 +13 4793 -1.691090e+03 8.753003e+01 +2 4794 -5.023300e+02 -6.923999e+01 +9 4794 -4.891899e+02 8.106006e+01 +2 4795 -2.553800e+02 -3.662000e+01 +10 4795 -2.222500e+02 -4.604000e+02 +11 4795 3.524399e+02 5.432001e+01 +13 4795 -1.689410e+03 1.807300e+02 +2 4796 -2.104200e+02 -2.803998e+01 +9 4796 -2.544500e+02 1.242300e+02 +10 4796 -1.910699e+02 -4.557300e+02 +11 4796 3.884800e+02 6.488000e+01 +13 4796 -1.550720e+03 1.966500e+02 +20 4796 -3.658300e+02 -2.330699e+02 +2 4797 -2.371900e+02 -1.866998e+01 +9 4797 -2.783400e+02 1.285601e+02 +11 4797 3.665000e+02 6.975000e+01 +18 4797 -4.480900e+02 -3.627002e+01 +20 4797 -3.795300e+02 -2.292000e+02 +2 4798 -4.930100e+02 -1.570001e+01 +11 4798 1.760000e+02 6.216998e+01 +2 4799 -1.907700e+02 -1.490002e+01 +11 4799 4.032400e+02 7.629999e+01 +13 4799 -1.493430e+03 2.293000e+02 +18 4799 -4.218199e+02 -3.271997e+01 +2 4800 -3.506600e+02 -3.280029e+00 +11 4800 2.793800e+02 7.471002e+01 +2 4801 -1.566800e+02 1.280029e+00 +11 4801 4.330200e+02 9.227002e+01 +2 4802 -2.827500e+02 8.950012e+00 +10 4802 -2.412500e+02 -4.359200e+02 +12 4802 -8.675300e+02 -5.537000e+02 +18 4802 -4.732700e+02 -2.576001e+01 +2 4803 -1.120500e+02 1.346997e+01 +11 4803 4.725400e+02 1.097500e+02 +13 4803 -1.205890e+03 2.869399e+02 +20 4803 -3.114000e+02 -2.075500e+02 +2 4804 -1.120500e+02 1.346997e+01 +11 4804 4.725400e+02 1.097500e+02 +18 4804 -3.684000e+02 -1.225000e+01 +20 4804 -3.114000e+02 -2.075500e+02 +2 4805 -1.589700e+02 2.814001e+01 +10 4805 -1.545500e+02 -4.237500e+02 +11 4805 4.303800e+02 1.122000e+02 +20 4805 -3.394800e+02 -2.064500e+02 +2 4806 -1.589700e+02 2.814001e+01 +11 4806 4.303800e+02 1.122000e+02 +20 4806 -3.394800e+02 -2.064500e+02 +2 4807 -2.225100e+02 2.953003e+01 +11 4807 3.794100e+02 1.082900e+02 +2 4808 -1.121200e+02 3.332001e+01 +11 4808 4.717800e+02 1.237800e+02 +2 4809 -2.720800e+02 4.959998e+01 +10 4809 -2.347500e+02 -4.130000e+02 +11 4809 3.388500e+02 1.169100e+02 +18 4809 -4.673900e+02 -5.719971e+00 +2 4810 -4.322200e+02 6.114001e+01 +9 4810 -4.356100e+02 1.809000e+02 +10 4810 -3.278800e+02 -4.079000e+02 +11 4810 2.199200e+02 1.194500e+02 +2 4811 -2.993500e+02 6.494000e+01 +10 4811 -2.511500e+02 -4.053800e+02 +11 4811 3.179399e+02 1.261300e+02 +12 4811 -8.775300e+02 -5.203600e+02 +18 4811 -4.822100e+02 2.299805e-01 +2 4812 -3.953800e+02 6.866998e+01 +11 4812 2.475000e+02 1.256500e+02 +2 4813 -2.909000e+02 9.466003e+01 +9 4813 -3.256100e+02 2.108700e+02 +10 4813 -2.456500e+02 -3.887900e+02 +11 4813 3.243700e+02 1.485900e+02 +2 4814 -3.301600e+02 9.934998e+01 +9 4814 -3.566400e+02 2.126000e+02 +11 4814 2.947600e+02 1.503000e+02 +2 4815 -4.689800e+02 9.901001e+01 +11 4815 1.929399e+02 1.462200e+02 +2 4816 -4.648900e+02 1.033100e+02 +9 4816 -4.608800e+02 2.122900e+02 +11 4816 1.959500e+02 1.489700e+02 +2 4817 -5.830100e+02 1.100000e+02 +9 4817 -5.504000e+02 2.154000e+02 +11 4817 1.108199e+02 1.521000e+02 +2 4818 -2.679200e+02 1.108400e+02 +9 4818 -3.059100e+02 2.249500e+02 +11 4818 3.421899e+02 1.624200e+02 +18 4818 -4.640200e+02 2.304004e+01 +20 4818 -3.930800e+02 -1.774900e+02 +2 4819 -2.679000e+02 1.222200e+02 +9 4819 -3.057800e+02 2.339700e+02 +11 4819 3.421000e+02 1.706900e+02 +20 4819 -3.929900e+02 -1.730500e+02 +2 4820 -2.639400e+02 1.397800e+02 +11 4820 3.454399e+02 1.838800e+02 +2 4821 -1.117900e+02 1.580900e+02 +9 4821 -1.593400e+02 2.852900e+02 +11 4821 4.728600e+02 2.198100e+02 +13 4821 -1.197860e+03 6.463000e+02 +18 4821 -3.672300e+02 5.828003e+01 +2 4822 -1.269900e+02 1.728600e+02 +11 4822 4.599700e+02 2.313000e+02 +2 4823 -5.002100e+02 1.770400e+02 +11 4823 1.699700e+02 2.026600e+02 +2 4824 4.974301e+02 1.801300e+02 +11 4824 9.759399e+02 2.552300e+02 +17 4824 -1.410160e+03 6.156799e+02 +2 4825 -3.952600e+02 1.815000e+02 +11 4825 2.460699e+02 2.082200e+02 +2 4826 -5.006300e+02 1.841400e+02 +11 4826 1.696600e+02 2.073800e+02 +2 4827 -5.340500e+02 1.855600e+02 +9 4827 -5.150700e+02 2.735701e+02 +11 4827 1.454800e+02 2.073100e+02 +2 4828 -2.711100e+02 1.983600e+02 +11 4828 3.390699e+02 2.270200e+02 +2 4829 -4.783600e+02 2.094800e+02 +11 4829 1.852600e+02 2.259500e+02 +2 4830 -3.098300e+02 2.133600e+02 +10 4830 -2.579100e+02 -3.246100e+02 +11 4830 3.094200e+02 2.345800e+02 +12 4830 -8.830200e+02 -4.310699e+02 +20 4830 -4.121600e+02 -1.370200e+02 +2 4831 -3.226900e+02 2.139200e+02 +11 4831 2.996400e+02 2.343400e+02 +2 4832 -4.371600e+02 2.190300e+02 +11 4832 2.154600e+02 2.341500e+02 +2 4833 -3.628800e+02 2.461600e+02 +11 4833 2.696200e+02 2.563000e+02 +2 4834 -3.767300e+02 2.454500e+02 +11 4834 2.598900e+02 2.550600e+02 +2 4835 -4.486200e+02 2.589900e+02 +11 4835 2.067700e+02 2.622300e+02 +12 4835 -9.714200e+02 -4.062600e+02 +2 4836 -4.481500e+02 2.979000e+02 +11 4836 2.073800e+02 2.923800e+02 +18 4836 -5.537300e+02 1.091699e+02 +2 4837 -3.510100e+02 3.009500e+02 +11 4837 2.792500e+02 2.971500e+02 +2 4838 -4.000600e+02 3.072700e+02 +9 4838 -4.134900e+02 3.693800e+02 +11 4838 2.423900e+02 2.999300e+02 +2 4839 -2.662000e+02 3.090300e+02 +11 4839 3.432200e+02 3.100200e+02 +2 4840 -4.874300e+02 3.086600e+02 +10 4840 -3.583000e+02 -2.743700e+02 +11 4840 1.789301e+02 2.982100e+02 +2 4841 -4.155400e+02 3.128400e+02 +9 4841 -4.256500e+02 3.726599e+02 +10 4841 -3.178300e+02 -2.718101e+02 +11 4841 2.311500e+02 3.034600e+02 +2 4842 -3.823100e+02 3.228900e+02 +11 4842 2.551200e+02 3.124000e+02 +18 4842 -5.213400e+02 1.219199e+02 +2 4843 -4.143700e+02 3.269900e+02 +11 4843 2.315100e+02 3.136100e+02 +2 4844 -3.016900e+02 3.289300e+02 +9 4844 -3.354301e+02 3.896599e+02 +11 4844 3.161100e+02 3.209400e+02 +18 4844 -4.809100e+02 1.264299e+02 +2 4845 -2.849300e+02 3.300200e+02 +11 4845 3.281300e+02 3.229700e+02 +2 4846 -3.619800e+02 3.414000e+02 +11 4846 2.702400e+02 3.267900e+02 +2 4847 -3.619800e+02 3.414000e+02 +11 4847 2.702400e+02 3.267900e+02 +2 4848 -3.578300e+02 3.470900e+02 +11 4848 2.735000e+02 3.309000e+02 +2 4849 -3.622000e+02 3.519900e+02 +10 4849 -2.871400e+02 -2.499301e+02 +11 4849 2.699500e+02 3.345000e+02 +2 4850 -2.661500e+02 3.534900e+02 +10 4850 -2.298300e+02 -2.483600e+02 +11 4850 3.428000e+02 3.415000e+02 +18 4850 -4.617600e+02 1.392500e+02 +2 4851 -3.297300e+02 3.573100e+02 +11 4851 2.940000e+02 3.406000e+02 +2 4852 -6.382400e+02 3.661200e+02 +10 4852 -4.384700e+02 -2.443800e+02 +2 4853 -6.250800e+02 3.711300e+02 +11 4853 7.953003e+01 3.410800e+02 +2 4854 -3.623000e+02 3.726500e+02 +11 4854 2.698900e+02 3.498800e+02 +2 4855 7.565400e+02 3.776500e+02 +7 4855 1.007980e+03 5.316400e+02 +9 4855 5.513301e+02 4.774099e+02 +17 4855 -1.002610e+03 9.043401e+02 +2 4856 -6.636800e+02 3.781000e+02 +11 4856 5.118994e+01 3.460000e+02 +12 4856 -1.099420e+03 -3.326801e+02 +2 4857 -5.281400e+02 3.883700e+02 +9 4857 -5.120100e+02 4.274299e+02 +11 4857 1.487100e+02 3.556600e+02 +2 4858 -5.043900e+02 3.901500e+02 +9 4858 -4.940400e+02 4.295200e+02 +2 4859 -4.030700e+02 3.918000e+02 +9 4859 -4.168199e+02 4.331699e+02 +11 4859 2.394700e+02 3.622300e+02 +2 4860 -3.668400e+02 3.960300e+02 +9 4860 -3.881700e+02 4.383700e+02 +11 4860 2.663900e+02 3.667200e+02 +2 4861 -6.183400e+02 4.046400e+02 +11 4861 8.405005e+01 3.659900e+02 +2 4862 -2.577900e+02 4.264299e+02 +9 4862 -2.988199e+02 4.699900e+02 +11 4862 3.500300e+02 3.989200e+02 +2 4863 -7.221200e+02 4.377900e+02 +9 4863 -6.589200e+02 4.656799e+02 +2 4864 -7.339200e+02 4.562100e+02 +9 4864 -6.683800e+02 4.790701e+02 +11 4864 4.699707e-01 4.029800e+02 +2 4865 -7.339200e+02 4.562100e+02 +9 4865 -6.683800e+02 4.790701e+02 +11 4865 4.699707e-01 4.029800e+02 +2 4866 -3.221900e+02 4.566400e+02 +9 4866 -3.532700e+02 4.862100e+02 +11 4866 3.001100e+02 4.141100e+02 +2 4867 -3.572900e+02 4.585900e+02 +10 4867 -2.825200e+02 -1.921899e+02 +12 4867 -9.066500e+02 -2.823199e+02 +18 4867 -5.073800e+02 1.889099e+02 +2 4868 -6.934100e+02 4.667700e+02 +11 4868 2.902002e+01 4.106200e+02 +2 4869 -4.914400e+02 4.681600e+02 +9 4869 -4.846600e+02 4.916300e+02 +18 4869 -5.726000e+02 1.915300e+02 +2 4870 -4.587200e+02 4.708900e+02 +9 4870 -4.604900e+02 4.918600e+02 +2 4871 -2.907000e+02 4.720400e+02 +11 4871 3.244301e+02 4.307800e+02 +2 4872 -2.907000e+02 4.720400e+02 +9 4872 -3.257900e+02 5.037400e+02 +10 4872 -2.426300e+02 -1.842700e+02 +11 4872 3.244301e+02 4.307800e+02 +2 4873 -4.152600e+02 4.770100e+02 +11 4873 2.306801e+02 4.240200e+02 +2 4874 -2.473900e+02 -2.002700e+02 +11 4874 3.591700e+02 -6.570001e+01 +2 4875 -2.606700e+02 -1.870200e+02 +9 4875 -2.982700e+02 -2.359985e+00 +11 4875 3.487800e+02 -5.652002e+01 +2 4876 -3.753200e+02 -1.850900e+02 +11 4876 2.625500e+02 -5.853998e+01 +2 4877 -2.954500e+02 -1.831200e+02 +11 4877 3.217400e+02 -5.538000e+01 +2 4878 3.372400e+02 -1.770100e+02 +11 4878 6.826801e+02 -1.085400e+02 +13 4878 -9.881500e+02 -9.676001e+01 +2 4879 -2.409600e+02 -1.672900e+02 +9 4879 -2.810200e+02 1.445996e+01 +11 4879 3.641801e+02 -4.088000e+01 +13 4879 -1.653590e+03 -1.453400e+02 +2 4880 -2.297300e+02 -1.651400e+02 +10 4880 -2.051200e+02 -5.299000e+02 +11 4880 3.728800e+02 -3.753998e+01 +13 4880 -1.618750e+03 -1.372300e+02 +2 4881 4.464399e+02 -1.601700e+02 +9 4881 -6.281995e+01 -8.626001e+01 +2 4882 -2.412700e+02 -1.373200e+02 +11 4882 3.639399e+02 -1.853003e+01 +13 4882 -1.652840e+03 -7.065002e+01 +2 4883 -1.872998e+01 -1.220000e+02 +9 4883 -1.396700e+02 3.497998e+01 +2 4884 -1.254800e+02 -8.528998e+01 +11 4884 4.606200e+02 3.179999e+01 +12 4884 -7.256600e+02 -5.994500e+02 +2 4885 -1.542400e+02 -8.248999e+01 +11 4885 4.349700e+02 3.028003e+01 +2 4886 -2.587000e+02 -8.170001e+01 +9 4886 -2.967000e+02 7.870996e+01 +11 4886 3.498400e+02 2.117999e+01 +13 4886 -1.703030e+03 6.896997e+01 +2 4887 -3.285700e+02 -8.146002e+01 +11 4887 2.965300e+02 1.803003e+01 +2 4888 -4.248700e+02 -7.940002e+01 +11 4888 2.255300e+02 1.733002e+01 +2 4889 -6.860999e+01 -7.445001e+01 +11 4889 5.214600e+02 5.746002e+01 +2 4890 -3.743300e+02 -6.573999e+01 +11 4890 2.628900e+02 2.817999e+01 +2 4891 -7.152002e+01 -6.488000e+01 +11 4891 5.181899e+02 6.445001e+01 +13 4891 -9.891300e+02 7.550000e+01 +20 4891 -2.774100e+02 -2.323000e+02 +2 4892 -2.269700e+02 -5.377002e+01 +9 4892 -2.680500e+02 1.025900e+02 +11 4892 3.752600e+02 4.313000e+01 +18 4892 -4.412800e+02 -5.493005e+01 +2 4893 -2.269700e+02 -5.377002e+01 +9 4893 -2.680500e+02 1.025900e+02 +18 4893 -4.412800e+02 -5.493005e+01 +20 4893 -3.741801e+02 -2.461300e+02 +2 4894 -1.677900e+02 -4.465002e+01 +10 4894 -1.610000e+02 -4.639900e+02 +11 4894 4.229500e+02 5.565997e+01 +12 4894 -7.713500e+02 -5.799301e+02 +2 4895 -3.917900e+02 -4.395001e+01 +11 4895 2.500900e+02 4.326001e+01 +2 4896 -4.198000e+02 -4.058002e+01 +9 4896 -4.263600e+02 1.037500e+02 +2 4897 -2.444500e+02 -3.812000e+01 +11 4897 3.616801e+02 5.391998e+01 +12 4897 -8.373000e+02 -5.803500e+02 +13 4897 -1.654740e+03 1.752400e+02 +2 4898 -3.976400e+02 -3.708002e+01 +9 4898 -4.082000e+02 1.070500e+02 +2 4899 -4.112100e+02 -3.720001e+01 +11 4899 2.355000e+02 4.801001e+01 +18 4899 -5.384600e+02 -4.922998e+01 +2 4900 -5.106200e+02 -3.721002e+01 +11 4900 1.632400e+02 4.665002e+01 +2 4901 -4.326200e+02 -3.671997e+01 +11 4901 2.202800e+02 4.791998e+01 +2 4902 -4.392900e+02 -3.663000e+01 +11 4902 2.144301e+02 4.792999e+01 +2 4903 -4.467800e+02 -3.656000e+01 +11 4903 2.101000e+02 4.784998e+01 +2 4904 -4.649100e+02 -3.654999e+01 +11 4904 1.965200e+02 4.752002e+01 +2 4905 4.785900e+02 -3.590997e+01 +11 4905 9.644100e+02 8.539001e+01 +2 4906 -4.856400e+02 -3.610999e+01 +11 4906 1.812800e+02 4.746002e+01 +2 4907 -2.264100e+02 -3.554999e+01 +9 4907 -2.689500e+02 1.169399e+02 +11 4907 3.752300e+02 5.753998e+01 +13 4907 -1.602740e+03 1.781000e+02 +2 4908 -1.248600e+02 -3.107001e+01 +11 4908 4.620800e+02 7.421002e+01 +2 4909 -1.863900e+02 -2.892999e+01 +11 4909 4.081400e+02 6.590002e+01 +2 4910 -3.309400e+02 -2.752002e+01 +10 4910 -2.700900e+02 -4.560300e+02 +11 4910 2.948101e+02 5.771002e+01 +2 4911 -1.703500e+02 -2.364001e+01 +11 4911 4.206300e+02 7.131000e+01 +2 4912 -4.047600e+02 -1.951001e+01 +9 4912 -4.143300e+02 1.200800e+02 +11 4912 2.402900e+02 6.150000e+01 +2 4913 -6.421997e+01 -1.665997e+01 +10 4913 -5.760999e+01 -4.468000e+02 +11 4913 5.254600e+02 1.032400e+02 +12 4913 -6.291600e+02 -5.441899e+02 +13 4913 -9.577900e+02 1.906899e+02 +18 4913 -3.224000e+02 -1.790002e+01 +20 4913 -2.725900e+02 -2.119200e+02 +2 4914 -2.199200e+02 -2.809998e+00 +11 4914 3.804301e+02 8.337000e+01 +13 4914 -1.581140e+03 2.610701e+02 +2 4915 -1.675400e+02 -1.820007e+00 +11 4915 4.232800e+02 8.833002e+01 +2 4916 -2.667900e+02 9.199829e-01 +9 4916 -3.040699e+02 1.397800e+02 +11 4916 3.433900e+02 8.073999e+01 +2 4917 -2.829200e+02 1.665002e+01 +11 4917 3.305601e+02 9.202002e+01 +2 4918 -2.268500e+02 2.208002e+01 +11 4918 3.750400e+02 1.004800e+02 +2 4919 -1.684600e+02 5.502002e+01 +9 4919 -2.174100e+02 1.922600e+02 +2 4920 -4.282000e+02 5.708002e+01 +11 4920 2.229399e+02 1.164200e+02 +2 4921 -3.871300e+02 6.025000e+01 +11 4921 2.528600e+02 1.195800e+02 +2 4922 -2.458400e+02 6.123999e+01 +11 4922 3.597700e+02 1.273900e+02 +13 4922 -1.656230e+03 4.226699e+02 +2 4923 -2.676400e+02 6.140002e+01 +11 4923 3.423000e+02 1.258200e+02 +2 4924 -2.929000e+02 6.152002e+01 +11 4924 3.230800e+02 1.243200e+02 +2 4925 -2.531800e+02 6.281000e+01 +11 4925 3.542900e+02 1.279700e+02 +13 4925 -1.679980e+03 4.275500e+02 +2 4926 -2.731200e+02 6.546997e+01 +11 4926 3.382900e+02 1.281100e+02 +2 4927 -2.935400e+02 6.821997e+01 +9 4927 -3.271600e+02 1.901000e+02 +2 4928 -1.385200e+02 7.178998e+01 +9 4928 -1.844600e+02 2.143600e+02 +10 4928 -1.340400e+02 -3.999100e+02 +13 4928 -1.289280e+03 4.329399e+02 +18 4928 -3.845601e+02 1.378003e+01 +2 4929 -2.457800e+02 7.426001e+01 +9 4929 -2.864600e+02 1.976899e+02 +10 4929 -2.153700e+02 -3.993900e+02 +11 4929 3.597300e+02 1.360800e+02 +12 4929 -8.350700e+02 -5.121801e+02 +13 4929 -1.654230e+03 4.520601e+02 +2 4930 -3.947300e+02 7.734003e+01 +9 4930 -4.089800e+02 1.940500e+02 +2 4931 -4.698000e+02 8.839001e+01 +11 4931 1.922100e+02 1.390400e+02 +2 4932 -2.459000e+02 1.019200e+02 +11 4932 3.596899e+02 1.585400e+02 +13 4932 -1.653090e+03 5.234600e+02 +2 4933 -5.909800e+02 1.038900e+02 +9 4933 -5.565100e+02 2.112300e+02 +11 4933 1.052400e+02 1.478100e+02 +2 4934 -4.498700e+02 1.062000e+02 +11 4934 2.071200e+02 1.517000e+02 +2 4935 -2.721600e+02 1.073300e+02 +11 4935 3.389200e+02 1.593400e+02 +2 4936 -4.649700e+02 1.115500e+02 +9 4936 -4.614600e+02 2.184299e+02 +11 4936 1.958900e+02 1.552200e+02 +18 4936 -5.635500e+02 2.266003e+01 +2 4937 -2.721100e+02 1.171700e+02 +10 4937 -2.336100e+02 -3.763900e+02 +11 4937 3.389700e+02 1.668100e+02 +2 4938 -2.720700e+02 1.366700e+02 +10 4938 -2.335900e+02 -3.659800e+02 +11 4938 3.388400e+02 1.810000e+02 +2 4939 -1.694100e+02 1.469500e+02 +11 4939 4.214000e+02 2.000700e+02 +2 4940 -3.671500e+02 1.737200e+02 +11 4940 2.670100e+02 2.034400e+02 +2 4941 -2.432800e+02 1.820200e+02 +9 4941 -2.850500e+02 2.828700e+02 +11 4941 3.616100e+02 2.181000e+02 +12 4941 -8.302700e+02 -4.457600e+02 +13 4941 -1.645630e+03 7.244100e+02 +2 4942 -1.727500e+02 1.845300e+02 +11 4942 4.190400e+02 2.264400e+02 +13 4942 -1.419670e+03 7.226799e+02 +18 4942 -4.080601e+02 6.393994e+01 +2 4943 -3.221400e+02 1.848300e+02 +10 4943 -2.649000e+02 -3.399900e+02 +12 4943 -8.916700e+02 -4.482600e+02 +2 4944 -4.411600e+02 1.885000e+02 +11 4944 2.126700e+02 2.117100e+02 +2 4945 -3.902900e+02 1.949000e+02 +9 4945 -4.051400e+02 2.828500e+02 +11 4945 2.501300e+02 2.173500e+02 +2 4946 4.925400e+02 1.970000e+02 +11 4946 9.736000e+02 2.711000e+02 +17 4946 -1.420660e+03 6.414299e+02 +2 4947 -2.860200e+02 2.007400e+02 +9 4947 -3.223400e+02 2.922300e+02 +11 4947 3.276700e+02 2.269800e+02 +2 4948 -1.747800e+02 2.013000e+02 +10 4948 -1.654200e+02 -3.296700e+02 +11 4948 4.170100e+02 2.418100e+02 +18 4948 -4.089399e+02 7.322998e+01 +2 4949 -3.612000e+02 2.041800e+02 +11 4949 2.711899e+02 2.255000e+02 +2 4950 -3.188200e+02 2.050700e+02 +9 4950 -3.491300e+02 2.935701e+02 +2 4951 -3.235700e+02 2.083100e+02 +9 4951 -3.525800e+02 2.961300e+02 +2 4952 -5.004400e+02 2.088400e+02 +9 4952 -4.895000e+02 2.921899e+02 +11 4952 1.695400e+02 2.253300e+02 +2 4953 -3.012900e+02 2.408900e+02 +9 4953 -3.356600e+02 3.210500e+02 +2 4954 -3.301400e+02 2.440500e+02 +11 4954 2.941899e+02 2.553700e+02 +2 4955 5.181899e+02 2.469100e+02 +11 4955 9.938600e+02 3.094100e+02 +12 4955 -2.927700e+02 -3.893000e+02 +17 4955 -1.376980e+03 7.171600e+02 +2 4956 -5.470000e+02 2.516700e+02 +11 4956 1.360500e+02 2.545700e+02 +2 4957 -2.507700e+02 2.533300e+02 +10 4957 -2.183000e+02 -3.020500e+02 +11 4957 3.556400e+02 2.704700e+02 +13 4957 -1.660670e+03 9.024800e+02 +2 4958 -3.715400e+02 2.626700e+02 +11 4958 2.632700e+02 2.682000e+02 +2 4959 -3.715400e+02 2.626700e+02 +11 4959 2.632700e+02 2.682000e+02 +2 4960 -3.735000e+02 2.740900e+02 +11 4960 2.618000e+02 2.760700e+02 +2 4961 -3.735000e+02 2.740900e+02 +11 4961 2.618000e+02 2.760700e+02 +2 4962 -2.748500e+02 2.746100e+02 +11 4962 3.360699e+02 2.825200e+02 +2 4963 -2.748500e+02 2.746100e+02 +11 4963 3.360699e+02 2.825200e+02 +2 4964 -3.501400e+02 2.752400e+02 +11 4964 2.791100e+02 2.783200e+02 +2 4965 -3.547800e+02 2.789300e+02 +11 4965 2.759000e+02 2.804300e+02 +2 4966 -3.649300e+02 2.846400e+02 +11 4966 2.674399e+02 2.863700e+02 +2 4967 -3.512300e+02 2.853900e+02 +11 4967 2.781700e+02 2.848600e+02 +2 4968 4.588000e+02 2.925900e+02 +11 4968 9.727700e+02 3.700400e+02 +2 4969 -3.906200e+02 2.988000e+02 +11 4969 2.484600e+02 2.950500e+02 +2 4970 -6.273900e+02 3.089400e+02 +11 4970 7.759998e+01 2.959800e+02 +2 4971 -4.300800e+02 3.123900e+02 +9 4971 -4.370601e+02 3.716400e+02 +2 4972 -4.245000e+02 3.131800e+02 +9 4972 -4.318800e+02 3.724099e+02 +11 4972 2.244800e+02 3.035000e+02 +2 4973 -3.620500e+02 3.164700e+02 +10 4973 -2.881400e+02 -2.695300e+02 +11 4973 2.702900e+02 3.083600e+02 +2 4974 -3.585600e+02 3.197800e+02 +9 4974 -3.813300e+02 3.797800e+02 +11 4974 2.729399e+02 3.108600e+02 +2 4975 -3.585900e+02 3.302200e+02 +9 4975 -3.814700e+02 3.870901e+02 +2 4976 -5.681400e+02 3.313200e+02 +9 4976 -5.423800e+02 3.837400e+02 +2 4977 -2.583800e+02 3.366500e+02 +9 4977 -3.002300e+02 3.996400e+02 +2 4978 -2.530200e+02 3.394300e+02 +9 4978 -2.948400e+02 4.017800e+02 +11 4978 3.531899e+02 3.333400e+02 +13 4978 -1.672830e+03 1.117400e+03 +2 4979 -2.568500e+02 3.551200e+02 +10 4979 -2.238500e+02 -2.461000e+02 +11 4979 3.499399e+02 3.456400e+02 +12 4979 -8.400600e+02 -3.407100e+02 +18 4979 -4.565699e+02 1.418101e+02 +2 4980 -7.794200e+02 3.626200e+02 +9 4980 -6.998000e+02 4.084900e+02 +2 4981 -4.719300e+02 3.637800e+02 +9 4981 -4.697300e+02 4.095701e+02 +2 4982 -5.209800e+02 3.852800e+02 +9 4982 -5.077900e+02 4.254500e+02 +11 4982 1.538900e+02 3.533700e+02 +2 4983 -3.618400e+02 3.916700e+02 +11 4983 2.701899e+02 3.638900e+02 +2 4984 -3.618400e+02 3.916700e+02 +11 4984 2.701899e+02 3.638900e+02 +2 4985 -3.381400e+02 3.925900e+02 +11 4985 2.881300e+02 3.658101e+02 +2 4986 -5.988400e+02 3.924500e+02 +11 4986 9.771997e+01 3.564200e+02 +2 4987 -2.518700e+02 4.021500e+02 +11 4987 3.551000e+02 3.825000e+02 +2 4988 -6.086800e+02 4.029600e+02 +9 4988 -5.736200e+02 4.382500e+02 +2 4989 -2.622200e+02 4.228700e+02 +9 4989 -3.021000e+02 4.664700e+02 +11 4989 3.464500e+02 3.954500e+02 +2 4990 -2.618500e+02 4.288700e+02 +11 4990 3.459900e+02 4.001500e+02 +2 4991 -6.245100e+02 4.325100e+02 +9 4991 -5.858900e+02 4.614399e+02 +2 4992 -3.022900e+02 4.434800e+02 +11 4992 3.152600e+02 4.060701e+02 +2 4993 -2.575900e+02 4.498400e+02 +11 4993 3.495500e+02 4.164100e+02 +2 4994 -3.527500e+02 4.538700e+02 +9 4994 -3.763500e+02 4.853301e+02 +2 4995 -3.108200e+02 4.590200e+02 +9 4995 -3.440800e+02 4.890701e+02 +2 4996 -6.957400e+02 4.616899e+02 +11 4996 2.802002e+01 4.070500e+02 +2 4997 -5.791300e+02 4.643201e+02 +11 4997 1.113000e+02 4.101500e+02 +12 4997 -1.047300e+03 -2.824800e+02 +2 4998 -5.049500e+02 4.686700e+02 +9 4998 -4.949600e+02 4.916400e+02 +2 4999 -5.852800e+02 4.725500e+02 +9 4999 -5.573900e+02 4.907200e+02 +2 5000 -5.852800e+02 4.725500e+02 +9 5000 -5.573900e+02 4.907200e+02 +2 5001 -6.295700e+02 4.744100e+02 +9 5001 -5.895300e+02 4.941000e+02 +2 5002 -7.195300e+02 4.744100e+02 +9 5002 -6.584300e+02 4.925100e+02 +2 5003 -4.196300e+02 4.804100e+02 +11 5003 2.272900e+02 4.264100e+02 +2 5004 -4.800100e+02 5.425800e+02 +9 5004 -4.722800e+02 5.560000e+02 +11 5004 1.837500e+02 4.793101e+02 +12 5004 -9.713700e+02 -2.291600e+02 +2 5005 -4.844400e+02 5.457600e+02 +9 5005 -4.754301e+02 5.580601e+02 +11 5005 1.811500e+02 4.815800e+02 +2 5006 -3.175400e+02 -2.118500e+02 +9 5006 -3.452300e+02 -2.367004e+01 +2 5007 -4.475400e+02 -2.041000e+02 +9 5007 -4.487200e+02 -2.012000e+01 +2 5008 -1.078000e+02 -1.990000e+02 +11 5008 4.772500e+02 -5.234998e+01 +2 5009 -2.602200e+02 -1.962100e+02 +9 5009 -2.979200e+02 -8.479980e+00 +2 5010 -2.500200e+02 -1.951100e+02 +10 5010 -2.189600e+02 -5.466600e+02 +11 5010 3.572000e+02 -6.171997e+01 +12 5010 -8.449800e+02 -6.760100e+02 +2 5011 -2.500200e+02 -1.951100e+02 +10 5011 -2.189600e+02 -5.466600e+02 +2 5012 -2.463400e+02 -1.945800e+02 +11 5012 3.600601e+02 -6.085999e+01 +2 5013 -2.463700e+02 -1.902700e+02 +11 5013 3.601300e+02 -5.721997e+01 +2 5014 -2.475300e+02 -1.795500e+02 +11 5014 3.591000e+02 -5.026001e+01 +13 5014 -1.674780e+03 -1.751100e+02 +2 5015 -2.605200e+02 -1.775200e+02 +10 5015 -2.265800e+02 -5.372600e+02 +2 5016 -3.041000e+02 -1.773100e+02 +11 5016 3.155400e+02 -5.103003e+01 +2 5017 -2.432300e+02 -1.766600e+02 +11 5017 3.625200e+02 -4.788000e+01 +13 5017 -1.660420e+03 -1.689301e+02 +2 5018 -1.666100e+02 -1.686200e+02 +9 5018 -2.146700e+02 1.958997e+01 +2 5019 -1.547400e+02 -9.134003e+01 +9 5019 -2.026300e+02 8.153003e+01 +11 5019 4.343700e+02 2.363000e+01 +13 5019 -1.370620e+03 3.514001e+01 +2 5020 -1.617600e+02 -9.079999e+01 +11 5020 4.281801e+02 2.241998e+01 +2 5021 -2.451500e+02 -8.846002e+01 +11 5021 3.605500e+02 1.734003e+01 +2 5022 -3.369100e+02 -6.932001e+01 +9 5022 -3.603300e+02 8.384998e+01 +11 5022 2.906100e+02 2.656000e+01 +2 5023 -3.609300e+02 -6.960999e+01 +11 5023 2.727000e+02 2.575000e+01 +2 5024 -3.766500e+02 -6.953998e+01 +11 5024 2.608199e+02 2.542999e+01 +2 5025 -1.242800e+02 -6.773999e+01 +11 5025 4.621200e+02 4.545001e+01 +2 5026 -1.689000e+02 -5.028003e+01 +9 5026 -2.175300e+02 1.103400e+02 +11 5026 4.218900e+02 5.153003e+01 +2 5027 -4.663300e+02 -4.308002e+01 +11 5027 1.955300e+02 4.319000e+01 +2 5028 -2.444300e+02 -4.173999e+01 +11 5028 3.613300e+02 5.092999e+01 +2 5029 -3.280300e+02 -3.740997e+01 +9 5029 -3.547000e+02 1.079700e+02 +11 5029 2.960000e+02 4.964001e+01 +2 5030 -3.781100e+02 -3.767999e+01 +11 5030 2.600500e+02 4.837000e+01 +2 5031 -2.746300e+02 -2.397998e+01 +11 5031 3.369000e+02 6.189001e+01 +2 5032 -4.403100e+02 -2.144000e+01 +11 5032 2.146600e+02 5.903003e+01 +2 5033 -2.083800e+02 -1.881000e+01 +11 5033 3.895900e+02 7.131000e+01 +13 5033 -1.548240e+03 2.208301e+02 +2 5034 -1.694600e+02 -1.728003e+01 +9 5034 -2.195900e+02 1.360601e+02 +11 5034 4.206100e+02 7.581000e+01 +18 5034 -4.099900e+02 -3.317004e+01 +2 5035 -2.245700e+02 -1.659998e+01 +11 5035 3.760000e+02 7.145001e+01 +13 5035 -1.600140e+03 2.277500e+02 +2 5036 -1.839600e+02 -7.409973e+00 +9 5036 -2.315500e+02 1.434099e+02 +2 5037 -2.689400e+02 7.119995e+00 +11 5037 3.408900e+02 8.707001e+01 +2 5038 -2.331900e+02 1.914001e+01 +9 5038 -2.743400e+02 1.580601e+02 +13 5038 -1.617880e+03 3.165801e+02 +2 5039 -2.099400e+02 2.671002e+01 +9 5039 -2.535601e+02 1.669399e+02 +11 5039 3.889000e+02 1.063100e+02 +2 5040 -2.099400e+02 2.671002e+01 +11 5040 3.889000e+02 1.063100e+02 +2 5041 -4.566600e+02 3.457001e+01 +11 5041 2.023400e+02 1.003700e+02 +2 5042 -4.566600e+02 3.457001e+01 +11 5042 2.023400e+02 1.003700e+02 +2 5043 -2.734500e+02 5.915997e+01 +11 5043 3.380200e+02 1.236600e+02 +2 5044 -2.967600e+02 1.109500e+02 +11 5044 3.196400e+02 1.605900e+02 +2 5045 -2.632900e+02 1.267600e+02 +11 5045 3.460900e+02 1.749200e+02 +2 5046 -8.476001e+01 1.423700e+02 +9 5046 -9.920996e+01 3.062000e+02 +13 5046 -9.528900e+02 5.982700e+02 +2 5047 -7.115997e+01 1.580800e+02 +9 5047 -8.828003e+01 3.187000e+02 +2 5048 -2.315200e+02 1.603100e+02 +9 5048 -2.743700e+02 2.674500e+02 +13 5048 -1.607250e+03 6.687200e+02 +2 5049 -2.404500e+02 1.628800e+02 +9 5049 -2.820900e+02 2.686899e+02 +13 5049 -1.633410e+03 6.758300e+02 +2 5050 -2.653200e+02 1.852100e+02 +9 5050 -3.038000e+02 2.826200e+02 +13 5050 -1.708500e+03 7.336000e+02 +2 5051 -1.894500e+02 1.927400e+02 +9 5051 -2.367700e+02 2.986000e+02 +10 5051 -1.759900e+02 -3.340200e+02 +11 5051 4.049200e+02 2.334400e+02 +13 5051 -1.471240e+03 7.459299e+02 +2 5052 -2.796000e+02 1.928500e+02 +11 5052 3.320500e+02 2.216700e+02 +2 5053 -1.872500e+02 1.995300e+02 +9 5053 -2.339500e+02 3.045601e+02 +11 5053 4.074399e+02 2.385400e+02 +13 5053 -1.460190e+03 7.620701e+02 +2 5054 -2.059100e+02 2.024200e+02 +9 5054 -2.533600e+02 3.047600e+02 +13 5054 -1.527700e+03 7.736500e+02 +2 5055 -2.059100e+02 2.024200e+02 +11 5055 3.913000e+02 2.386300e+02 +2 5056 -2.898100e+02 2.035300e+02 +9 5056 -3.255400e+02 2.942000e+02 +2 5057 -2.136300e+02 2.052400e+02 +11 5057 3.855100e+02 2.388700e+02 +13 5057 -1.546750e+03 7.781600e+02 +2 5058 -2.057400e+02 2.089300e+02 +9 5058 -2.514200e+02 3.095601e+02 +11 5058 3.912900e+02 2.438900e+02 +13 5058 -1.521230e+03 7.889500e+02 +2 5059 -2.942600e+02 2.239200e+02 +11 5059 3.212300e+02 2.429200e+02 +2 5060 -2.942600e+02 2.239200e+02 +11 5060 3.212300e+02 2.429200e+02 +2 5061 -3.284300e+02 2.507400e+02 +11 5061 2.956100e+02 2.599100e+02 +2 5062 -3.709100e+02 2.767200e+02 +11 5062 2.636600e+02 2.796300e+02 +2 5063 -3.531000e+02 3.050900e+02 +9 5063 -3.767700e+02 3.684099e+02 +11 5063 2.769800e+02 2.999900e+02 +2 5064 -4.923800e+02 3.128300e+02 +9 5064 -4.843400e+02 3.702400e+02 +11 5064 1.750601e+02 3.010200e+02 +2 5065 -3.621100e+02 3.290100e+02 +11 5065 2.699800e+02 3.172300e+02 +2 5066 -3.426700e+02 3.548600e+02 +9 5066 -3.696899e+02 4.065400e+02 +11 5066 2.842400e+02 3.371600e+02 +2 5067 -4.067700e+02 3.604200e+02 +11 5067 2.371000e+02 3.383400e+02 +2 5068 -3.744000e+02 3.827900e+02 +9 5068 -3.943900e+02 4.270601e+02 +2 5069 -2.475500e+02 3.853100e+02 +9 5069 -2.895900e+02 4.405500e+02 +11 5069 3.574700e+02 3.706000e+02 +2 5070 -6.734100e+02 3.903700e+02 +9 5070 -6.224300e+02 4.289299e+02 +2 5071 -6.669300e+02 3.911400e+02 +9 5071 -6.174900e+02 4.291300e+02 +2 5072 -6.669300e+02 3.911400e+02 +9 5072 -6.174900e+02 4.291300e+02 +11 5072 4.881995e+01 3.555701e+02 +2 5073 -5.132100e+02 3.913400e+02 +9 5073 -5.010800e+02 4.308301e+02 +2 5074 -6.702400e+02 3.939900e+02 +9 5074 -6.200500e+02 4.313600e+02 +11 5074 4.628003e+01 3.579600e+02 +2 5075 -6.702400e+02 3.939900e+02 +9 5075 -6.200500e+02 4.313600e+02 +2 5076 -6.508000e+02 3.955900e+02 +9 5076 -6.054900e+02 4.325500e+02 +11 5076 6.028003e+01 3.592800e+02 +2 5077 -6.508000e+02 3.955900e+02 +9 5077 -6.054900e+02 4.325500e+02 +2 5078 -6.668600e+02 3.976600e+02 +9 5078 -6.176500e+02 4.339800e+02 +2 5079 -6.473500e+02 3.980300e+02 +11 5079 6.270996e+01 3.609700e+02 +2 5080 -6.637700e+02 4.002600e+02 +11 5080 5.117004e+01 3.625900e+02 +2 5081 -5.131800e+02 4.010500e+02 +9 5081 -5.012700e+02 4.376799e+02 +11 5081 1.591801e+02 3.655100e+02 +2 5082 -6.574500e+02 4.010600e+02 +11 5082 5.551001e+01 3.633500e+02 +2 5083 -6.574500e+02 4.010600e+02 +9 5083 -6.104000e+02 4.370901e+02 +11 5083 5.551001e+01 3.633500e+02 +2 5084 -3.362600e+02 4.249700e+02 +11 5084 2.896200e+02 3.901700e+02 +2 5085 -4.313600e+02 4.449700e+02 +11 5085 2.190500e+02 4.010701e+02 +2 5086 -2.752300e+02 4.668400e+02 +11 5086 3.368600e+02 4.294800e+02 +2 5087 -4.092200e+02 4.790100e+02 +11 5087 2.349399e+02 4.257600e+02 +2 5088 -1.312400e+02 -2.192800e+02 +9 5088 -1.793900e+02 -1.575000e+01 +2 5089 -2.467600e+02 -1.762400e+02 +11 5089 3.594200e+02 -4.682001e+01 +2 5090 -1.695600e+02 -1.657600e+02 +9 5090 -2.173199e+02 2.181995e+01 +2 5091 -2.665400e+02 -1.647100e+02 +11 5091 3.436000e+02 -4.092999e+01 +2 5092 -1.671000e+02 -1.637600e+02 +11 5092 4.239500e+02 -3.316998e+01 +2 5093 -2.681100e+02 -2.239001e+01 +9 5093 -3.055500e+02 1.230000e+02 +2 5094 -4.696700e+02 -1.940997e+01 +11 5094 1.928400e+02 6.026001e+01 +2 5095 -7.142999e+01 -1.390997e+01 +11 5095 5.183199e+02 1.040000e+02 +2 5096 -1.683300e+02 8.510010e+00 +11 5096 4.225000e+02 9.653003e+01 +2 5097 -2.524700e+02 1.381300e+02 +11 5097 3.539500e+02 1.843600e+02 +2 5098 -2.724400e+02 1.564700e+02 +11 5098 3.386700e+02 1.957000e+02 +2 5099 -2.036100e+02 2.050700e+02 +11 5099 3.943199e+02 2.407200e+02 +13 5099 -1.512240e+03 7.773700e+02 +2 5100 5.273300e+02 2.263900e+02 +11 5100 1.001030e+03 2.929900e+02 +17 5100 -1.361780e+03 6.845701e+02 +2 5101 -2.579300e+02 2.735300e+02 +9 5101 -2.980500e+02 3.520400e+02 +2 5102 -4.924800e+02 2.925300e+02 +11 5102 1.747900e+02 2.861100e+02 +2 5103 7.919200e+02 3.024200e+02 +8 5103 9.807500e+02 5.325000e+02 +17 5103 -9.146100e+02 7.847900e+02 +2 5104 7.864900e+02 3.024700e+02 +8 5104 9.727400e+02 5.317800e+02 +2 5105 -3.410500e+02 3.888000e+02 +9 5105 -3.677300e+02 4.340100e+02 +3 5106 -9.047500e+02 1.722800e+02 +9 5106 -3.186500e+02 1.489600e+02 +20 5106 -4.013199e+02 -2.187900e+02 +3 5107 -7.451900e+02 -2.935699e+02 +9 5107 -2.664700e+02 -2.168994e+01 +13 5107 -1.605630e+03 -2.690400e+02 +20 5107 -3.751300e+02 -3.116100e+02 +3 5108 -7.178000e+02 2.845200e+02 +10 5108 -1.978500e+02 -3.808000e+02 +12 5108 -8.123500e+02 -4.884301e+02 +13 5108 -1.576670e+03 5.372900e+02 +3 5109 -8.860800e+02 3.403900e+02 +9 5109 -3.149800e+02 2.212500e+02 +10 5109 -2.378199e+02 -3.823900e+02 +18 5109 -4.701500e+02 2.173999e+01 +3 5110 -8.400500e+02 -3.595400e+02 +10 5110 -2.259301e+02 -5.793400e+02 +12 5110 -8.542900e+02 -7.129000e+02 +20 5110 -3.920800e+02 -3.281500e+02 +3 5111 -7.792100e+02 -2.287000e+02 +11 5111 3.660400e+02 -5.194000e+01 +3 5112 -4.449600e+02 -2.339100e+02 +11 5112 4.669301e+02 -2.125000e+01 +3 5113 -4.451900e+02 -2.123800e+02 +11 5113 4.672400e+02 -1.115002e+01 +3 5114 -3.057400e+02 -5.679999e+01 +10 5114 -6.862000e+01 -4.354301e+02 +11 5114 5.126700e+02 1.174900e+02 +13 5114 -1.004580e+03 2.460300e+02 +18 5114 -3.314301e+02 -7.290039e+00 +20 5114 -2.808900e+02 -2.034399e+02 +3 5115 -6.747300e+02 -2.612600e+02 +9 5115 -2.449800e+02 -2.270020e+00 +13 5115 -1.528470e+03 -2.171000e+02 +3 5116 -3.101000e+02 -8.712000e+01 +10 5116 -6.985999e+01 -4.492600e+02 +12 5116 -6.453500e+02 -5.473400e+02 +13 5116 -1.014560e+03 1.846000e+02 +3 5117 -4.395200e+02 2.421200e+02 +10 5117 -1.183101e+02 -3.576000e+02 +13 5117 -1.214760e+03 6.208800e+02 +18 5117 -3.703300e+02 5.329004e+01 +3 5118 6.203101e+02 -3.223700e+02 +9 5118 1.752200e+02 -7.845996e+01 +3 5119 -3.776000e+02 -1.327200e+02 +9 5119 -1.396899e+02 1.072800e+02 +13 5119 -1.133660e+03 5.894995e+01 +18 5119 -3.557500e+02 -5.194995e+01 +20 5119 -3.009600e+02 -2.423500e+02 +3 5120 -2.951900e+02 -1.245700e+02 +9 5120 -1.017200e+02 1.379199e+02 +11 5120 5.177200e+02 7.635999e+01 +13 5120 -9.899100e+02 1.186100e+02 +18 5120 -3.286801e+02 -3.367004e+01 +20 5120 -2.778400e+02 -2.263400e+02 +3 5121 -1.020670e+03 9.641998e+01 +10 5121 -2.700900e+02 -4.560300e+02 +18 5121 -4.982100e+02 -4.389001e+01 +3 5122 -4.523900e+02 1.475500e+02 +9 5122 -1.701899e+02 2.270400e+02 +13 5122 -1.236680e+03 4.675200e+02 +3 5123 -3.111100e+02 1.609400e+02 +10 5123 -7.084998e+01 -3.240500e+02 +11 5123 4.952600e+02 2.845900e+02 +3 5124 -5.850000e+02 3.820701e+02 +11 5124 4.221300e+02 2.311800e+02 +12 5124 -7.676400e+02 -4.366500e+02 +3 5125 2.903900e+02 3.545001e+01 +11 5125 8.909100e+02 2.063400e+02 +3 5126 -2.620000e+02 -2.678800e+02 +9 5126 -8.191003e+01 5.796997e+01 +11 5126 5.355400e+02 -1.330017e+00 +3 5127 -2.072700e+02 -2.445900e+02 +9 5127 -5.430005e+01 1.774500e+02 +3 5128 -2.072700e+02 -2.445900e+02 +9 5128 -5.430005e+01 1.774500e+02 +3 5129 -2.064200e+02 -2.203600e+02 +9 5129 -5.365002e+01 1.983700e+02 +13 5129 -7.493400e+02 1.146300e+02 +4 5130 -1.738600e+02 7.145701e+02 +7 5130 -1.192980e+03 9.874700e+02 +15 5130 5.444700e+02 6.220400e+02 +4 5131 -1.911700e+02 6.229500e+02 +7 5131 -1.212990e+03 8.523201e+02 +4 5132 9.155601e+02 4.793900e+02 +5 5132 4.568000e+02 9.125500e+02 +4 5133 1.031440e+03 3.655000e+02 +5 5133 6.311300e+02 7.792900e+02 +4 5134 1.119980e+03 3.559700e+02 +5 5134 7.518700e+02 7.771200e+02 +4 5135 1.123310e+03 3.981400e+02 +5 5135 7.536599e+02 8.254200e+02 +4 5136 1.087660e+03 4.252300e+02 +5 5136 6.950200e+02 8.570400e+02 +4 5137 -2.191400e+02 2.911799e+02 +5 5137 -1.037700e+03 4.402000e+02 +4 5138 1.012850e+03 4.399700e+02 +5 5138 5.984200e+02 8.690699e+02 +4 5139 4.369100e+02 5.210300e+02 +10 5139 -9.168900e+02 -1.254800e+02 +14 5139 1.812500e+02 3.695100e+02 +19 5139 1.220470e+03 5.732200e+02 +4 5140 -3.008300e+02 2.495400e+02 +5 5140 -1.133670e+03 3.635601e+02 +19 5140 -8.318005e+01 1.315901e+02 +4 5141 1.172330e+03 3.392100e+02 +5 5141 8.203301e+02 7.595601e+02 +4 5142 1.196340e+03 3.444099e+02 +5 5142 8.496201e+02 7.698300e+02 +16 5142 6.446100e+02 3.672300e+02 +4 5143 7.832800e+02 3.803201e+02 +9 5143 -4.607200e+02 3.093700e+02 +12 5143 -9.783900e+02 -4.230200e+02 +16 5143 3.323400e+02 4.049500e+02 +4 5144 -1.128800e+02 4.020601e+02 +7 5144 -1.068540e+03 4.932300e+02 +4 5145 1.089180e+03 4.031799e+02 +5 5145 6.986200e+02 8.323101e+02 +4 5146 9.453501e+02 4.655801e+02 +5 5146 5.006200e+02 8.962200e+02 +4 5147 -1.979800e+02 5.976100e+02 +5 5147 -1.081860e+03 8.705601e+02 +16 5147 -6.842000e+02 6.438101e+02 +4 5148 -2.790300e+02 6.296400e+02 +5 5148 -1.197870e+03 8.983199e+02 +14 5148 -3.337000e+02 5.477700e+02 +15 5148 4.267900e+02 5.254700e+02 +16 5148 -7.856700e+02 6.816700e+02 +19 5148 -3.664001e+01 8.294399e+02 +4 5149 1.319140e+03 2.657500e+02 +8 5149 3.294500e+02 -2.678998e+01 +16 5149 7.210900e+02 2.916799e+02 +4 5150 1.308600e+03 2.800701e+02 +5 5150 1.002630e+03 7.021100e+02 +8 5150 3.094900e+02 1.302002e+01 +4 5151 1.317170e+03 2.907100e+02 +5 5151 1.012020e+03 7.157600e+02 +8 5151 3.250100e+02 3.281000e+01 +4 5152 -3.388800e+02 3.598401e+02 +5 5152 -1.210640e+03 5.085800e+02 +4 5153 1.091930e+03 3.666899e+02 +5 5153 7.101400e+02 7.877900e+02 +4 5154 1.473550e+03 3.793301e+02 +5 5154 1.159480e+03 8.811400e+02 +4 5155 1.000860e+03 3.810300e+02 +5 5155 5.869399e+02 7.940400e+02 +4 5156 1.018230e+03 3.947600e+02 +5 5156 6.082600e+02 8.139800e+02 +4 5157 9.690300e+02 4.374000e+02 +5 5157 5.412800e+02 8.583500e+02 +4 5158 9.690300e+02 4.374000e+02 +5 5158 5.408400e+02 8.580900e+02 +4 5159 -2.857100e+02 5.866600e+02 +5 5159 -1.198730e+03 8.367200e+02 +7 5159 -1.369360e+03 7.998300e+02 +14 5159 -3.394700e+02 5.105500e+02 +15 5159 4.210500e+02 4.787200e+02 +19 5159 -4.872998e+01 7.540800e+02 +4 5160 -2.662800e+02 6.061400e+02 +5 5160 -1.173510e+03 8.679000e+02 +16 5160 -7.686700e+02 6.549500e+02 +4 5161 1.213190e+03 2.846300e+02 +5 5161 8.828999e+02 6.965800e+02 +16 5161 6.560601e+02 3.100500e+02 +4 5162 1.196280e+03 3.090100e+02 +5 5162 8.557000e+02 7.257100e+02 +8 5162 8.015002e+01 1.103500e+02 +4 5163 1.184490e+03 3.115200e+02 +5 5163 8.404500e+02 7.277300e+02 +8 5163 5.553003e+01 1.206800e+02 +4 5164 9.876201e+02 3.540300e+02 +5 5164 5.739000e+02 7.582600e+02 +4 5165 9.876201e+02 3.540300e+02 +5 5165 5.739000e+02 7.582600e+02 +4 5166 1.052910e+03 3.582200e+02 +5 5166 6.611801e+02 7.711100e+02 +4 5167 1.052910e+03 3.582200e+02 +5 5167 6.611801e+02 7.711100e+02 +4 5168 1.013090e+03 3.593500e+02 +9 5168 -2.260800e+02 2.809800e+02 +13 5168 -1.436260e+03 6.878000e+02 +20 5168 -3.483199e+02 -1.481700e+02 +4 5169 -3.055100e+02 3.609099e+02 +5 5169 -1.166910e+03 5.166100e+02 +4 5170 1.424700e+03 3.807500e+02 +8 5170 4.635200e+02 1.475200e+02 +4 5171 1.066090e+03 4.112100e+02 +5 5171 6.665500e+02 8.421700e+02 +4 5172 1.415400e+03 4.291400e+02 +8 5172 4.426600e+02 2.414900e+02 +16 5172 7.298900e+02 4.362200e+02 +4 5173 9.109399e+02 4.684299e+02 +5 5173 4.491400e+02 8.972000e+02 +4 5174 -2.518400e+02 4.848101e+02 +5 5174 -1.127680e+03 7.012000e+02 +7 5174 -1.304560e+03 6.324200e+02 +14 5174 -3.090300e+02 4.170100e+02 +15 5174 4.600300e+02 3.662400e+02 +16 5174 -7.437700e+02 5.168000e+02 +19 5174 1.169995e+01 5.719399e+02 +4 5175 -6.642004e+01 6.054299e+02 +5 5175 -8.996600e+02 9.083300e+02 +4 5176 -5.787000e+01 6.247300e+02 +5 5176 -8.924300e+02 9.361200e+02 +14 5176 -1.274700e+02 5.305900e+02 +19 5176 3.741300e+02 8.444700e+02 +4 5177 -5.787000e+01 6.247300e+02 +5 5177 -8.924300e+02 9.361200e+02 +19 5177 3.741300e+02 8.444700e+02 +4 5178 1.301240e+03 2.105100e+02 +8 5178 3.006000e+02 -1.428700e+02 +4 5179 7.922500e+02 2.308401e+02 +9 5179 -4.366700e+02 6.512000e+01 +4 5180 -3.200000e+02 2.464399e+02 +5 5180 -1.159540e+03 3.562400e+02 +19 5180 -1.174100e+02 1.244800e+02 +4 5181 7.926001e+02 2.719500e+02 +9 5181 -4.404399e+02 1.300000e+02 +20 5181 -4.684399e+02 -2.278500e+02 +4 5182 1.298380e+03 2.874500e+02 +5 5182 9.890300e+02 7.098500e+02 +8 5182 2.899399e+02 3.119000e+01 +16 5182 7.095000e+02 3.134200e+02 +4 5183 -3.115699e+02 3.120100e+02 +5 5183 -1.164320e+03 4.485200e+02 +4 5184 1.195900e+03 3.334500e+02 +5 5184 8.517700e+02 7.563700e+02 +4 5185 -3.131200e+02 3.706200e+02 +5 5185 -1.182390e+03 5.290800e+02 +19 5185 -1.025100e+02 3.561799e+02 +4 5186 1.067410e+03 3.800300e+02 +5 5186 6.753800e+02 8.020500e+02 +4 5187 9.835601e+02 3.834099e+02 +5 5187 5.627200e+02 7.953600e+02 +4 5188 9.817900e+02 3.914600e+02 +5 5188 5.607300e+02 8.047200e+02 +4 5189 1.068080e+03 4.023201e+02 +5 5189 6.713199e+02 8.317900e+02 +4 5190 1.428050e+03 4.305300e+02 +8 5190 4.666899e+02 2.436600e+02 +16 5190 7.399600e+02 4.372200e+02 +4 5191 -2.812000e+02 4.471500e+02 +5 5191 -1.156990e+03 6.433900e+02 +4 5192 -2.812000e+02 4.471500e+02 +5 5192 -1.156990e+03 6.433900e+02 +4 5193 9.823799e+02 4.490200e+02 +5 5193 5.585400e+02 8.751801e+02 +4 5194 9.171299e+02 4.601500e+02 +5 5194 4.600601e+02 8.873900e+02 +4 5195 4.666300e+02 4.683101e+02 +11 5195 -5.475800e+02 4.339900e+02 +14 5195 2.147800e+02 3.342900e+02 +4 5196 -3.221700e+02 4.814900e+02 +5 5196 -1.223000e+03 6.822300e+02 +15 5196 3.786300e+02 3.617000e+02 +16 5196 -8.289100e+02 5.144399e+02 +19 5196 -1.171100e+02 5.597200e+02 +4 5197 -1.700500e+02 6.739200e+02 +7 5197 -1.174540e+03 9.187300e+02 +4 5198 -1.298700e+02 6.757300e+02 +7 5198 -1.124940e+03 9.172800e+02 +15 5198 5.952400e+02 5.787600e+02 +16 5198 -6.164300e+02 7.264000e+02 +19 5198 2.368000e+02 9.150000e+02 +4 5199 1.315140e+03 2.498201e+02 +8 5199 3.254900e+02 -5.919000e+01 +16 5199 7.202800e+02 2.793300e+02 +4 5200 1.044600e+03 2.529500e+02 +5 5200 6.706600e+02 6.341000e+02 +4 5201 -2.237700e+02 2.788600e+02 +5 5201 -1.038110e+03 4.219099e+02 +14 5201 -2.896200e+02 2.309900e+02 +16 5201 -7.027300e+02 2.881400e+02 +4 5202 1.292820e+03 2.816400e+02 +5 5202 9.824700e+02 7.020200e+02 +8 5202 2.810900e+02 1.900000e+01 +16 5202 7.074700e+02 3.079299e+02 +4 5203 1.099660e+03 3.113401e+02 +5 5203 7.308700e+02 7.161300e+02 +4 5204 1.023230e+03 3.158500e+02 +5 5204 6.281200e+02 7.139900e+02 +4 5205 1.185530e+03 3.287700e+02 +5 5205 8.390400e+02 7.493400e+02 +4 5206 1.006180e+03 3.329000e+02 +5 5206 6.031500e+02 7.322500e+02 +4 5207 -3.144200e+02 3.602800e+02 +5 5207 -1.181030e+03 5.142700e+02 +19 5207 -1.060900e+02 3.362500e+02 +4 5208 1.083760e+03 3.657900e+02 +5 5208 6.997000e+02 7.855300e+02 +4 5209 1.029320e+03 3.676200e+02 +5 5209 6.267300e+02 7.812300e+02 +4 5210 -2.579600e+02 3.782400e+02 +5 5210 -1.108660e+03 5.520500e+02 +19 5210 -1.420044e+00 3.741899e+02 +4 5211 9.586399e+02 3.936899e+02 +5 5211 5.302000e+02 8.043300e+02 +4 5212 1.370900e+02 4.081699e+02 +11 5212 -8.995900e+02 3.313600e+02 +16 5212 -3.235000e+02 4.306600e+02 +19 5212 7.302200e+02 4.213201e+02 +20 5212 -1.124730e+03 -6.783997e+01 +4 5213 1.099780e+03 4.223800e+02 +5 5213 7.128800e+02 8.579500e+02 +4 5214 9.175801e+02 4.746000e+02 +5 5214 4.578199e+02 9.070601e+02 +4 5215 -2.808400e+02 5.256400e+02 +7 5215 -1.358400e+03 7.022700e+02 +14 5215 -3.354700e+02 4.556200e+02 +15 5215 4.266700e+02 4.111300e+02 +19 5215 -4.037000e+01 6.453800e+02 +4 5216 -3.322900e+02 5.921500e+02 +5 5216 -1.264300e+03 8.356200e+02 +14 5216 -3.834400e+02 5.178600e+02 +15 5216 3.687900e+02 4.831700e+02 +16 5216 -8.465100e+02 6.409399e+02 +19 5216 -1.316600e+02 7.586300e+02 +4 5217 -8.858997e+01 5.928600e+02 +5 5217 -9.290000e+02 8.861899e+02 +4 5218 -2.602000e+02 5.973900e+02 +5 5218 -1.166430e+03 8.576300e+02 +14 5218 -3.139700e+02 5.191100e+02 +16 5218 -7.590700e+02 6.444399e+02 +4 5219 -2.602000e+02 5.973900e+02 +5 5219 -1.166430e+03 8.576300e+02 +7 5219 -1.321930e+03 8.122900e+02 +14 5219 -3.139700e+02 5.191100e+02 +15 5219 4.503101e+02 4.907600e+02 +16 5219 -7.590700e+02 6.444399e+02 +19 5219 -2.410034e+00 7.761000e+02 +4 5220 -4.912000e+01 6.032000e+02 +7 5220 -9.741500e+02 7.926200e+02 +15 5220 6.950900e+02 5.022200e+02 +4 5221 -3.215601e+02 6.132500e+02 +5 5221 -1.255340e+03 8.673800e+02 +4 5222 1.151680e+03 1.694299e+02 +5 5222 8.239900e+02 5.420800e+02 +4 5223 -2.842100e+02 2.250901e+02 +5 5223 -1.105440e+03 3.345000e+02 +19 5223 -5.352002e+01 8.591992e+01 +4 5224 -2.855100e+02 2.299299e+02 +5 5224 -1.109010e+03 3.408201e+02 +4 5225 1.205660e+03 2.512500e+02 +5 5225 8.791299e+02 6.532700e+02 +8 5225 1.070400e+02 -3.112000e+01 +4 5226 1.045130e+03 2.753700e+02 +5 5226 6.662900e+02 6.619700e+02 +4 5227 1.207510e+03 2.866400e+02 +5 5227 8.747300e+02 6.979600e+02 +8 5227 1.083101e+02 5.308002e+01 +4 5228 1.169070e+03 2.916000e+02 +5 5228 8.252600e+02 6.995601e+02 +4 5229 -3.223900e+02 2.974600e+02 +5 5229 -1.175780e+03 4.260100e+02 +19 5229 -1.206801e+02 2.203500e+02 +4 5230 -3.312600e+02 3.211599e+02 +5 5230 -1.192270e+03 4.576200e+02 +4 5231 1.047910e+03 3.271200e+02 +5 5231 6.599800e+02 7.309399e+02 +4 5232 1.024000e+03 3.396500e+02 +5 5232 6.253800e+02 7.434500e+02 +4 5233 1.049590e+03 3.425000e+02 +5 5233 6.587000e+02 7.502200e+02 +4 5234 1.129610e+03 3.603500e+02 +5 5234 7.587200e+02 7.841600e+02 +4 5235 1.384940e+03 3.717400e+02 +5 5235 1.091630e+03 8.108600e+02 +8 5235 3.958400e+02 1.342400e+02 +4 5236 -3.295200e+02 3.822200e+02 +5 5236 -1.206160e+03 5.420000e+02 +4 5237 1.273850e+03 3.972400e+02 +8 5237 2.243101e+02 2.598300e+02 +4 5238 9.534299e+02 4.141100e+02 +5 5238 5.208101e+02 8.309299e+02 +4 5239 -3.651801e+02 4.233301e+02 +5 5239 -1.264470e+03 5.906100e+02 +4 5240 -3.514100e+02 4.355701e+02 +5 5240 -1.250200e+03 6.119000e+02 +15 5240 3.446100e+02 3.106400e+02 +16 5240 -8.627000e+02 4.624299e+02 +4 5241 -3.388900e+02 4.358101e+02 +5 5241 -1.234170e+03 6.143000e+02 +4 5242 -1.375300e+02 4.439000e+02 +5 5242 -9.611600e+02 6.690701e+02 +4 5243 -3.603101e+02 4.438700e+02 +5 5243 -1.264850e+03 6.210500e+02 +15 5243 3.339500e+02 3.199000e+02 +16 5243 -8.737900e+02 4.719399e+02 +4 5244 -2.620699e+02 4.525500e+02 +7 5244 -1.320970e+03 5.825400e+02 +16 5244 -7.546100e+02 4.820200e+02 +19 5244 -8.319946e+00 5.103600e+02 +4 5245 -1.863500e+02 4.562400e+02 +5 5245 -1.030970e+03 6.757300e+02 +4 5246 4.079100e+02 4.580801e+02 +9 5246 -1.398520e+03 5.018201e+02 +11 5246 -6.933200e+02 4.212400e+02 +14 5246 1.603900e+02 3.252900e+02 +20 5246 -9.793300e+02 -1.671997e+01 +4 5247 -3.164900e+02 4.708500e+02 +5 5247 -1.211650e+03 6.681899e+02 +19 5247 -1.065800e+02 5.404199e+02 +4 5248 4.509700e+02 4.824000e+02 +10 5248 -8.899500e+02 -1.674000e+02 +16 5248 -4.648999e+01 5.025400e+02 +19 5248 1.251740e+03 5.147200e+02 +4 5249 -2.727300e+02 4.857800e+02 +7 5249 -1.342200e+03 6.363101e+02 +4 5250 9.284199e+02 4.893800e+02 +5 5250 4.700500e+02 9.268800e+02 +4 5251 -2.552000e+02 4.995601e+02 +5 5251 -1.135880e+03 7.221500e+02 +4 5252 -3.081400e+02 5.661899e+02 +5 5252 -1.225460e+03 8.036600e+02 +19 5252 -8.756006e+01 7.164299e+02 +4 5253 -2.398000e+02 5.670200e+02 +5 5253 -1.131440e+03 8.189900e+02 +7 5253 -1.286020e+03 7.616300e+02 +14 5253 -2.957700e+02 4.909500e+02 +15 5253 4.742900e+02 4.577800e+02 +16 5253 -7.338600e+02 6.097800e+02 +19 5253 3.456995e+01 7.232600e+02 +4 5254 -7.760010e+00 5.690400e+02 +7 5254 -9.155000e+02 7.360100e+02 +14 5254 -8.712000e+01 4.756700e+02 +15 5254 7.415200e+02 4.638900e+02 +19 5254 4.681000e+02 7.386000e+02 +4 5255 2.843994e+01 5.709800e+02 +5 5255 -7.545500e+02 8.768800e+02 +4 5256 -1.136801e+02 5.765900e+02 +7 5256 -1.073980e+03 7.606899e+02 +16 5256 -5.885400e+02 6.179700e+02 +4 5257 1.978003e+01 5.988700e+02 +7 5257 -8.789700e+02 7.775200e+02 +14 5257 -6.389999e+01 4.984600e+02 +15 5257 7.714800e+02 4.984500e+02 +16 5257 -4.416400e+02 6.380500e+02 +19 5257 5.192600e+02 7.932100e+02 +4 5258 1.248999e+01 6.092000e+02 +7 5258 -8.902300e+02 7.942700e+02 +14 5258 -7.082999e+01 5.078300e+02 +15 5258 7.633700e+02 5.096700e+02 +19 5258 5.041600e+02 8.110000e+02 +4 5259 -1.158600e+02 7.237600e+02 +7 5259 -1.121750e+03 9.888501e+02 +14 5259 -1.919600e+02 6.076700e+02 +15 5259 6.059600e+02 6.316400e+02 +19 5259 2.613900e+02 9.893799e+02 +4 5260 1.117680e+03 1.840400e+02 +5 5260 7.791799e+02 5.557200e+02 +4 5261 4.856006e+01 2.053301e+02 +11 5261 -9.469600e+02 -6.235999e+01 +16 5261 -3.999800e+02 2.136500e+02 +4 5262 1.159780e+03 2.221400e+02 +5 5262 8.259700e+02 6.091400e+02 +4 5263 -2.100300e+02 2.411300e+02 +7 5263 -1.221990e+03 2.462100e+02 +14 5263 -2.743600e+02 1.963500e+02 +15 5263 5.061100e+02 9.303998e+01 +19 5263 8.571997e+01 1.196200e+02 +4 5264 1.085020e+03 2.443000e+02 +5 5264 7.255699e+02 6.286899e+02 +4 5265 1.205640e+03 2.461799e+02 +5 5265 8.800100e+02 6.461300e+02 +8 5265 1.072400e+02 -4.278998e+01 +4 5266 1.318130e+03 2.575801e+02 +8 5266 3.298600e+02 -4.128003e+01 +4 5267 1.486790e+03 2.597000e+02 +5 5267 1.195770e+03 7.292500e+02 +8 5267 8.238900e+02 5.803003e+01 +16 5267 9.653600e+02 2.938500e+02 +4 5268 -1.450200e+02 2.730000e+02 +7 5268 -1.116350e+03 2.945400e+02 +14 5268 -2.143800e+02 2.226500e+02 +4 5269 -1.451000e+02 2.791300e+02 +7 5269 -1.116360e+03 3.040200e+02 +14 5269 -2.141400e+02 2.283400e+02 +15 5269 5.823600e+02 1.355100e+02 +16 5269 -6.097300e+02 2.897800e+02 +19 5269 2.092100e+02 1.927000e+02 +4 5270 -1.451000e+02 2.791300e+02 +5 5270 -9.293500e+02 4.309600e+02 +7 5270 -1.116350e+03 2.945400e+02 +14 5270 -2.143800e+02 2.226500e+02 +15 5270 5.822500e+02 1.284000e+02 +19 5270 2.091899e+02 1.811100e+02 +4 5271 1.026440e+03 3.099000e+02 +5 5271 6.340100e+02 7.057100e+02 +4 5272 -2.120500e+02 3.104099e+02 +5 5272 -1.032120e+03 4.679299e+02 +19 5272 8.358997e+01 2.513900e+02 +4 5273 -2.044800e+02 3.134000e+02 +5 5273 -1.021650e+03 4.742000e+02 +4 5274 1.043950e+03 3.170300e+02 +5 5274 6.569500e+02 7.170800e+02 +4 5275 -1.451400e+02 3.256799e+02 +7 5275 -1.118020e+03 3.763000e+02 +4 5276 1.108030e+03 3.273700e+02 +5 5276 7.387900e+02 7.385300e+02 +4 5277 -3.279301e+02 3.286400e+02 +5 5277 -1.190550e+03 4.667100e+02 +19 5277 -1.307500e+02 2.750701e+02 +4 5278 1.044880e+03 3.298401e+02 +5 5278 6.558101e+02 7.340601e+02 +4 5279 -3.284500e+02 3.441500e+02 +5 5279 -1.195070e+03 4.894399e+02 +19 5279 -1.310400e+02 3.058401e+02 +4 5280 1.005190e+03 3.553000e+02 +5 5280 5.977400e+02 7.615601e+02 +4 5281 1.056120e+03 3.590801e+02 +5 5281 6.648000e+02 7.732500e+02 +4 5282 1.075440e+03 3.660701e+02 +5 5282 6.893800e+02 7.849500e+02 +4 5283 1.106610e+03 3.779800e+02 +5 5283 7.284200e+02 8.024700e+02 +4 5284 1.408730e+03 3.822200e+02 +8 5284 4.371899e+02 1.540900e+02 +4 5285 -2.454800e+02 3.945200e+02 +5 5285 -1.094390e+03 5.775400e+02 +4 5286 9.500601e+02 4.158900e+02 +5 5286 5.150100e+02 8.320300e+02 +4 5287 1.180800e+03 4.170400e+02 +8 5287 4.131995e+01 3.637900e+02 +4 5288 -1.606300e+02 4.398700e+02 +5 5288 -9.939900e+02 6.579399e+02 +4 5289 -2.878400e+02 4.404299e+02 +5 5289 -1.165520e+03 6.324100e+02 +15 5289 4.181100e+02 3.168000e+02 +4 5290 -3.120300e+02 4.500100e+02 +5 5290 -1.200720e+03 6.405400e+02 +15 5290 3.899700e+02 3.270500e+02 +4 5291 9.604700e+02 4.512500e+02 +5 5291 5.255200e+02 8.784000e+02 +8 5291 -4.944600e+02 5.532600e+02 +4 5292 -2.542300e+02 4.526799e+02 +7 5292 -1.309860e+03 5.823300e+02 +15 5292 4.559700e+02 3.304800e+02 +19 5292 6.449951e+00 5.122200e+02 +4 5293 -2.482700e+02 4.637800e+02 +7 5293 -1.298210e+03 5.994500e+02 +15 5293 4.640400e+02 3.430500e+02 +16 5293 -7.391900e+02 4.941300e+02 +4 5294 -2.482700e+02 4.637800e+02 +5 5294 -1.116210e+03 6.731000e+02 +7 5294 -1.298210e+03 5.994500e+02 +15 5294 4.640400e+02 3.430500e+02 +16 5294 -7.391900e+02 4.941300e+02 +4 5295 -1.394700e+02 4.739600e+02 +7 5295 -1.110550e+03 6.054200e+02 +14 5295 -2.032500e+02 4.034800e+02 +15 5295 5.922200e+02 3.560701e+02 +19 5295 2.207900e+02 5.615701e+02 +4 5296 -1.454600e+02 4.738800e+02 +5 5296 -9.782800e+02 7.092000e+02 +14 5296 -2.090200e+02 4.034500e+02 +15 5296 5.843199e+02 3.556400e+02 +19 5296 2.100699e+02 5.606000e+02 +4 5297 8.942600e+02 4.844900e+02 +5 5297 4.254900e+02 9.160601e+02 +4 5298 9.157800e+02 4.876300e+02 +5 5298 4.517700e+02 9.241899e+02 +4 5299 9.155601e+02 4.918600e+02 +5 5299 4.506899e+02 9.290800e+02 +4 5300 -1.505400e+02 5.288500e+02 +5 5300 -1.000380e+03 7.848600e+02 +15 5300 5.793400e+02 4.175500e+02 +19 5300 2.012500e+02 6.648101e+02 +4 5301 -2.983000e+02 5.632900e+02 +5 5301 -1.210260e+03 8.018700e+02 +4 5302 -2.838500e+02 5.643101e+02 +7 5302 -1.365230e+03 7.635000e+02 +14 5302 -3.377600e+02 4.904000e+02 +15 5302 4.236300e+02 4.538101e+02 +16 5302 -7.865100e+02 6.078900e+02 +4 5303 -2.208300e+02 5.681000e+02 +5 5303 -1.105450e+03 8.247400e+02 +4 5304 -2.287500e+02 5.677600e+02 +7 5304 -1.266440e+03 7.614800e+02 +14 5304 -2.849400e+02 4.911600e+02 +19 5304 5.507996e+01 7.258600e+02 +4 5305 -2.019000e+02 5.694800e+02 +5 5305 -1.080200e+03 8.301899e+02 +7 5305 -1.219520e+03 7.602900e+02 +14 5305 -2.595400e+02 4.912000e+02 +15 5305 5.191500e+02 4.612700e+02 +16 5305 -6.885300e+02 6.114299e+02 +19 5305 1.037700e+02 7.313700e+02 +4 5306 -7.194995e+01 5.762400e+02 +7 5306 -1.006230e+03 7.549000e+02 +15 5306 6.698500e+02 4.718000e+02 +4 5307 -8.780029e+00 5.795601e+02 +7 5307 -9.160600e+02 7.521899e+02 +4 5308 -3.843994e+01 5.815100e+02 +7 5308 -9.581700e+02 7.587500e+02 +4 5309 4.057996e+01 6.225100e+02 +5 5309 -7.439200e+02 9.476100e+02 +7 5309 -8.597300e+02 8.098300e+02 +14 5309 -5.092999e+01 5.123199e+02 +15 5309 7.921899e+02 5.238500e+02 +16 5309 -4.242400e+02 6.614301e+02 +19 5309 5.553600e+02 8.280701e+02 +4 5310 -2.267300e+02 6.419000e+02 +5 5310 -1.131910e+03 9.269399e+02 +15 5310 4.902300e+02 5.410400e+02 +16 5310 -7.215400e+02 6.936700e+02 +4 5311 -1.714800e+02 6.524700e+02 +5 5311 -1.057200e+03 9.535200e+02 +15 5311 5.565500e+02 5.546200e+02 +19 5311 1.638300e+02 8.885300e+02 +4 5312 -1.693101e+02 6.574100e+02 +5 5312 -1.055910e+03 9.596700e+02 +15 5312 5.563500e+02 5.601899e+02 +4 5313 1.274800e+02 6.899500e+02 +7 5313 -7.989600e+02 8.967100e+02 +4 5314 7.537000e+01 6.923101e+02 +7 5314 -8.911400e+02 9.122300e+02 +4 5315 1.119720e+03 1.552000e+02 +5 5315 7.860400e+02 5.187400e+02 +4 5316 1.071400e+03 2.232200e+02 +5 5316 7.116899e+02 5.993000e+02 +4 5317 -2.216600e+02 2.436500e+02 +7 5317 -1.246470e+03 2.500701e+02 +14 5317 -2.870500e+02 1.986100e+02 +15 5317 4.913199e+02 9.583002e+01 +16 5317 -6.976300e+02 2.485700e+02 +4 5318 1.082560e+03 2.475000e+02 +5 5318 7.216000e+02 6.320800e+02 +4 5319 -1.453500e+02 2.903401e+02 +7 5319 -1.117230e+03 3.213800e+02 +14 5319 -2.139800e+02 2.385500e+02 +15 5319 5.825000e+02 1.481900e+02 +19 5319 2.082700e+02 2.141400e+02 +4 5320 -3.056801e+02 3.146000e+02 +5 5320 -1.156240e+03 4.529500e+02 +4 5321 1.187600e+03 3.247600e+02 +5 5321 8.423999e+02 7.441000e+02 +4 5322 1.019460e+03 3.315400e+02 +5 5322 6.201700e+02 7.331300e+02 +4 5323 -1.846801e+02 3.484399e+02 +5 5323 -1.002890e+03 5.270200e+02 +19 5323 1.355200e+02 3.242800e+02 +4 5324 1.468810e+03 3.529399e+02 +5 5324 1.157860e+03 8.461899e+02 +4 5325 9.892600e+02 3.654700e+02 +5 5325 5.748700e+02 7.735701e+02 +4 5326 1.478630e+03 3.665300e+02 +5 5326 1.167210e+03 8.653700e+02 +4 5327 9.981499e+02 3.712100e+02 +5 5327 5.854100e+02 7.816300e+02 +4 5328 1.108190e+03 3.725500e+02 +5 5328 7.304700e+02 7.971500e+02 +4 5329 1.396290e+03 3.872900e+02 +5 5329 1.101480e+03 8.308500e+02 +8 5329 4.150699e+02 1.630700e+02 +4 5330 1.083380e+03 4.000400e+02 +5 5330 6.918600e+02 8.299299e+02 +4 5331 9.744399e+02 4.349900e+02 +5 5331 5.515200e+02 8.561600e+02 +4 5332 9.554199e+02 4.364399e+02 +5 5332 5.189800e+02 8.597800e+02 +4 5333 3.755500e+02 4.430601e+02 +11 5333 -7.962800e+02 4.010300e+02 +19 5333 1.097130e+03 4.281500e+02 +4 5334 -1.826600e+02 4.494800e+02 +7 5334 -1.232670e+03 5.711400e+02 +4 5335 9.031699e+02 4.619500e+02 +5 5335 4.402600e+02 8.884700e+02 +4 5336 -2.519800e+02 4.664600e+02 +5 5336 -1.124080e+03 6.756300e+02 +4 5337 3.762300e+02 4.762900e+02 +9 5337 -1.498920e+03 5.419600e+02 +10 5337 -1.015360e+03 -1.694900e+02 +14 5337 1.282900e+02 3.367700e+02 +16 5337 -1.305700e+02 4.947600e+02 +19 5337 1.098780e+03 4.860200e+02 +20 5337 -1.034050e+03 6.179993e+00 +4 5338 -3.088101e+02 4.874299e+02 +5 5338 -1.205990e+03 6.930200e+02 +4 5339 8.295000e+02 4.912900e+02 +10 5339 -2.963199e+02 -1.902200e+02 +4 5340 4.480699e+02 5.008500e+02 +9 5340 -1.329220e+03 5.792800e+02 +10 5340 -9.042600e+02 -1.444900e+02 +11 5340 -6.308100e+02 4.946799e+02 +16 5340 -5.407001e+01 5.204100e+02 +19 5340 1.239600e+03 5.415400e+02 +20 5340 -9.395400e+02 2.367999e+01 +4 5341 -2.588400e+02 5.011200e+02 +5 5341 -1.141270e+03 7.231500e+02 +14 5341 -3.152700e+02 4.325900e+02 +15 5341 4.521801e+02 3.838800e+02 +4 5342 -1.741000e+02 5.050000e+02 +7 5342 -1.169260e+03 6.567200e+02 +19 5342 1.554301e+02 6.166899e+02 +4 5343 -6.222998e+01 5.057300e+02 +5 5343 -8.703600e+02 7.698400e+02 +15 5343 6.801000e+02 3.921600e+02 +19 5343 3.665300e+02 6.235900e+02 +4 5344 -2.709700e+02 5.205100e+02 +7 5344 -1.338050e+03 6.925200e+02 +15 5344 4.386700e+02 4.062200e+02 +4 5345 -4.278500e+02 5.731500e+02 +7 5345 -1.376240e+03 7.914600e+02 +4 5346 -2.883000e+02 5.736000e+02 +5 5346 -1.202480e+03 8.176400e+02 +14 5346 -3.417800e+02 4.998400e+02 +19 5346 -5.405005e+01 7.319100e+02 +4 5347 -2.610100e+02 5.775800e+02 +5 5347 -1.162690e+03 8.296400e+02 +4 5348 -3.276600e+02 5.899700e+02 +5 5348 -1.258080e+03 8.330701e+02 +4 5349 -2.464301e+02 5.956600e+02 +5 5349 -1.147090e+03 8.580100e+02 +4 5350 -1.700900e+02 6.006600e+02 +7 5350 -1.200050e+03 8.062400e+02 +4 5351 8.464001e+01 6.122900e+02 +5 5351 -6.814200e+02 9.430500e+02 +4 5352 1.378003e+01 6.315900e+02 +7 5352 -8.869000e+02 8.269600e+02 +16 5352 -4.501800e+02 6.736600e+02 +4 5353 -2.004200e+02 6.403101e+02 +7 5353 -1.217220e+03 8.718900e+02 +16 5353 -6.887900e+02 6.912400e+02 +19 5353 1.089200e+02 8.620500e+02 +4 5354 -1.579700e+02 7.329100e+02 +7 5354 -1.156000e+03 1.010030e+03 +14 5354 -2.173700e+02 6.320000e+02 +19 5354 1.867400e+02 1.028830e+03 +5 5355 4.310400e+02 6.320300e+02 +9 5355 -3.419399e+02 1.355000e+02 +10 5355 -2.592200e+02 -4.442300e+02 +11 5355 3.085900e+02 7.492999e+01 +12 5355 -8.881900e+02 -5.658700e+02 +18 5355 -4.887200e+02 -3.305005e+01 +20 5355 -4.144900e+02 -2.269100e+02 +5 5356 9.567200e+02 8.842900e+02 +8 5356 2.467300e+02 3.216700e+02 +5 5357 8.299399e+02 6.969299e+02 +8 5357 2.996997e+01 7.019000e+01 +16 5357 6.312900e+02 3.163600e+02 +5 5358 8.303899e+02 7.124900e+02 +8 5358 3.613000e+01 9.833002e+01 +5 5359 3.061500e+02 8.287600e+02 +8 5359 -9.892900e+02 5.831500e+02 +5 5360 8.044500e+02 8.520300e+02 +8 5360 1.515002e+01 3.548201e+02 +16 5360 6.146400e+02 4.292900e+02 +5 5361 3.676000e+02 5.978500e+02 +9 5361 -3.975699e+02 1.027800e+02 +10 5361 -3.024200e+02 -4.647800e+02 +18 5361 -5.260500e+02 -5.173999e+01 +20 5361 -4.460601e+02 -2.433600e+02 +5 5362 1.192020e+03 6.406700e+02 +8 5362 7.970200e+02 -1.217600e+02 +5 5363 8.543000e+02 6.576100e+02 +8 5363 6.659998e+01 -1.392999e+01 +5 5364 1.178640e+03 8.057000e+02 +8 5364 7.973199e+02 2.122400e+02 +5 5365 3.297600e+02 8.797100e+02 +8 5365 -9.186200e+02 6.790400e+02 +5 5366 1.217840e+03 6.231799e+02 +8 5366 8.531700e+02 -1.642000e+02 +5 5367 3.787400e+02 6.234500e+02 +9 5367 -3.920000e+02 1.348401e+02 +5 5368 8.428501e+02 6.306600e+02 +8 5368 4.051001e+01 -5.887000e+01 +5 5369 8.608701e+02 6.988700e+02 +8 5369 8.447998e+01 6.163000e+01 +5 5370 8.608701e+02 6.988700e+02 +8 5370 8.447998e+01 6.163000e+01 +5 5371 -9.893300e+02 7.516500e+02 +7 5371 -1.123880e+03 6.531100e+02 +14 5371 -2.093800e+02 4.311300e+02 +19 5371 2.058800e+02 6.162400e+02 +5 5372 7.822000e+02 7.958800e+02 +8 5372 -2.871997e+01 2.740800e+02 +5 5373 -1.186450e+03 8.119200e+02 +7 5373 -1.355210e+03 7.695500e+02 +14 5373 -3.326500e+02 4.942000e+02 +15 5373 4.287000e+02 4.582500e+02 +16 5373 -7.808100e+02 6.119200e+02 +19 5373 -3.678003e+01 7.224800e+02 +5 5374 9.436499e+02 8.823800e+02 +8 5374 2.266700e+02 3.274700e+02 +5 5375 3.250900e+02 9.014600e+02 +8 5375 -9.208600e+02 7.290699e+02 +5 5376 3.158600e+02 9.070900e+02 +8 5376 -9.375100e+02 7.427000e+02 +5 5377 -9.455600e+02 5.301899e+02 +7 5377 -1.116990e+03 4.057600e+02 +15 5377 5.835800e+02 2.100600e+02 +19 5377 2.101300e+02 3.175400e+02 +5 5378 -9.648900e+02 6.390300e+02 +7 5378 -1.116070e+03 5.270801e+02 +14 5378 -2.085500e+02 3.580900e+02 +19 5378 2.132300e+02 4.656699e+02 +5 5379 8.671799e+02 6.583101e+02 +8 5379 8.575000e+01 -1.678998e+01 +5 5380 8.613999e+02 6.924000e+02 +8 5380 8.393994e+01 4.653998e+01 +5 5381 8.613999e+02 6.924000e+02 +8 5381 8.393994e+01 4.653998e+01 +5 5382 9.792800e+02 7.321000e+02 +8 5382 2.771200e+02 7.157001e+01 +5 5383 7.581399e+02 8.002900e+02 +8 5383 -6.809998e+01 2.962800e+02 +5 5384 8.677800e+02 6.375100e+02 +8 5384 8.370996e+01 -5.522998e+01 +5 5385 -1.127690e+03 6.789800e+02 +7 5385 -1.310770e+03 6.085400e+02 +14 5385 -3.124100e+02 4.035000e+02 +15 5385 4.575200e+02 3.488400e+02 +16 5385 -7.469000e+02 5.001500e+02 +5 5386 -9.771300e+02 6.931200e+02 +7 5386 -1.119850e+03 5.969200e+02 +14 5386 -2.089600e+02 3.983600e+02 +15 5386 5.839700e+02 3.492100e+02 +5 5387 8.787000e+02 7.108600e+02 +8 5387 1.172600e+02 7.415002e+01 +5 5388 -9.841300e+02 7.114000e+02 +7 5388 -1.126790e+03 6.099900e+02 +15 5388 5.805800e+02 3.584900e+02 +5 5389 1.239490e+03 7.579900e+02 +6 5389 9.414500e+02 -6.075000e+01 +12 5389 -1.782200e+02 -5.688900e+02 +17 5389 -8.489700e+02 3.107600e+02 +20 5389 6.084998e+01 -2.290000e+02 +5 5390 1.094180e+03 8.053900e+02 +8 5390 3.986300e+02 1.255800e+02 +5 5391 7.498000e+02 8.053600e+02 +8 5391 -8.290997e+01 3.097900e+02 +5 5392 -1.236250e+03 8.106200e+02 +7 5392 -1.416870e+03 7.797500e+02 +15 5392 3.901899e+02 4.617100e+02 +19 5392 -1.006801e+02 7.261100e+02 +5 5393 1.104320e+03 8.353300e+02 +8 5393 4.194900e+02 1.691500e+02 +5 5394 7.093800e+02 8.700601e+02 +8 5394 -1.445900e+02 4.420300e+02 +5 5395 9.606399e+02 8.764900e+02 +8 5395 2.558300e+02 3.140800e+02 +5 5396 -1.039620e+03 8.790400e+02 +7 5396 -1.159770e+03 8.036200e+02 +5 5397 -1.164760e+03 9.110100e+02 +7 5397 -1.310120e+03 8.709800e+02 +14 5397 -3.062500e+02 5.508300e+02 +15 5397 4.598199e+02 5.322200e+02 +16 5397 -7.527200e+02 6.859301e+02 +19 5397 1.269995e+01 8.416899e+02 +5 5398 -1.157020e+03 9.126100e+02 +7 5398 -1.300730e+03 8.706000e+02 +14 5398 -3.004400e+02 5.506400e+02 +15 5398 4.662000e+02 5.325800e+02 +16 5398 -7.447500e+02 6.862800e+02 +19 5398 2.442004e+01 8.425701e+02 +5 5399 -1.056100e+03 9.339900e+02 +7 5399 -1.246400e+03 8.681899e+02 +5 5400 -1.062070e+03 9.522400e+02 +7 5400 -1.170700e+03 8.863000e+02 +16 5400 -6.586700e+02 7.037800e+02 +5 5401 9.676899e+02 6.103300e+02 +8 5401 2.422900e+02 -1.383300e+02 +5 5402 8.843201e+02 6.426400e+02 +8 5402 1.139900e+02 -5.217999e+01 +5 5403 -8.636800e+02 6.995300e+02 +7 5403 -9.984800e+02 5.719700e+02 +14 5403 -1.396800e+02 3.823400e+02 +5 5404 9.505100e+02 7.411899e+02 +8 5404 2.345601e+02 9.857001e+01 +5 5405 1.181810e+03 7.593201e+02 +8 5405 7.960500e+02 1.203800e+02 +5 5406 1.180050e+03 7.795000e+02 +8 5406 7.960400e+02 1.612200e+02 +5 5407 7.113101e+02 8.613500e+02 +8 5407 -1.436200e+02 4.250500e+02 +5 5408 -8.593400e+02 8.911801e+02 +7 5408 -9.645900e+02 7.727900e+02 +15 5408 7.033300e+02 4.877100e+02 +18 5408 -1.438920e+03 3.852300e+02 +20 5408 -1.231330e+03 1.309299e+02 +5 5409 9.923899e+02 6.030300e+02 +8 5409 2.806200e+02 -1.589200e+02 +5 5410 1.205090e+03 6.384800e+02 +8 5410 8.316899e+02 -1.282800e+02 +5 5411 8.544399e+02 6.387600e+02 +8 5411 6.340002e+01 -4.759998e+01 +5 5412 1.283010e+03 6.509500e+02 +8 5412 9.941700e+02 -1.243300e+02 +9 5412 5.833899e+02 2.339001e+01 +12 5412 -1.529100e+02 -6.609301e+02 +5 5413 1.112620e+03 6.901300e+02 +8 5413 4.358300e+02 -5.415002e+01 +5 5414 9.878799e+02 6.929100e+02 +6 5414 1.915900e+02 -1.646300e+02 +8 5414 2.867500e+02 2.030029e+00 +5 5415 9.830901e+02 6.928900e+02 +6 5415 1.873300e+02 -1.629500e+02 +8 5415 2.792900e+02 3.549988e+00 +5 5416 8.245601e+02 7.397600e+02 +8 5416 3.239001e+01 1.506800e+02 +5 5417 1.000110e+03 7.651100e+02 +8 5417 3.049100e+02 1.157500e+02 +5 5418 8.241899e+02 8.036200e+02 +8 5418 4.312000e+01 2.640200e+02 +5 5419 1.072690e+03 8.431400e+02 +8 5419 3.883101e+02 1.995600e+02 +5 5420 1.101540e+03 8.531200e+02 +8 5420 4.169800e+02 1.970700e+02 +5 5421 -9.970800e+02 8.624200e+02 +7 5421 -1.105450e+03 7.733700e+02 +5 5422 9.530100e+02 8.761000e+02 +8 5422 2.433900e+02 3.155900e+02 +5 5423 -1.160950e+03 9.117400e+02 +7 5423 -1.305660e+03 8.707200e+02 +16 5423 -7.486900e+02 6.863800e+02 +5 5424 3.823199e+02 9.132100e+02 +8 5424 -7.911300e+02 7.244100e+02 +5 5425 -1.136690e+03 9.197900e+02 +7 5425 -1.270370e+03 8.722100e+02 +19 5425 5.223999e+01 8.536200e+02 +20 5425 -1.459180e+03 2.110701e+02 +6 5426 4.793300e+02 -2.373700e+02 +7 5426 7.198999e+02 3.106000e+02 +9 5426 -4.547998e+01 2.776100e+02 +13 5426 -6.957400e+02 2.746699e+02 +6 5427 4.008400e+02 -3.313800e+02 +10 5427 -1.993994e+01 -5.119200e+02 +18 5427 -3.000200e+02 -5.268994e+01 +6 5428 7.816801e+02 3.486100e+02 +8 5428 9.427600e+02 6.664800e+02 +6 5429 4.153900e+02 -3.503101e+02 +9 5429 -5.943994e+01 8.447998e+01 +18 5429 -2.901500e+02 -6.637000e+01 +6 5430 4.151100e+02 -2.909800e+02 +9 5430 -6.308997e+01 1.608201e+02 +13 5430 -7.807900e+02 6.540039e+00 +16 5430 8.733400e+02 2.742800e+02 +18 5430 -2.909700e+02 -2.051001e+01 +6 5431 2.375000e+02 -1.153998e+01 +9 5431 -2.235699e+02 4.453800e+02 +11 5431 3.766700e+02 3.703400e+02 +16 5431 7.354700e+02 4.421600e+02 +6 5432 4.410400e+02 -3.005100e+02 +9 5432 -3.748999e+01 1.537600e+02 +11 5432 5.448800e+02 9.001001e+01 +13 5432 -7.046600e+02 -2.173999e+01 +7 5433 -4.143700e+02 5.088800e+02 +9 5433 -1.298740e+03 4.519199e+02 +10 5433 -8.852800e+02 -2.235400e+02 +11 5433 -6.023200e+02 3.739200e+02 +14 5433 1.973500e+02 3.110100e+02 +16 5433 -4.289001e+01 4.579399e+02 +18 5433 -1.081180e+03 1.791400e+02 +7 5434 1.229670e+03 5.213800e+02 +9 5434 8.147300e+02 4.629800e+02 +18 5434 2.353199e+02 1.524299e+02 +7 5435 -1.982600e+02 5.473000e+02 +9 5435 -9.254300e+02 4.944600e+02 +11 5435 -2.420000e+02 4.148500e+02 +7 5436 1.279130e+03 3.158700e+02 +10 5436 6.356299e+02 -4.002500e+02 +12 5436 1.145900e+02 -5.312700e+02 +7 5437 1.279130e+03 3.158700e+02 +9 5437 9.165701e+02 1.937800e+02 +10 5437 6.356299e+02 -4.002500e+02 +12 5437 1.145900e+02 -5.312700e+02 +20 5437 2.567300e+02 -2.048500e+02 +7 5438 1.097370e+03 2.160100e+02 +9 5438 7.197900e+02 7.078003e+01 +10 5438 5.003401e+02 -4.871300e+02 +12 5438 -4.629004e+01 -6.321200e+02 +18 5438 1.713199e+02 -8.958997e+01 +7 5439 1.009230e+03 2.495400e+02 +9 5439 6.172200e+02 1.152700e+02 +12 5439 -1.274301e+02 -5.856100e+02 +18 5439 1.070601e+02 -5.292004e+01 +20 5439 9.925000e+01 -2.440200e+02 +7 5440 1.098730e+03 3.044900e+02 +9 5440 7.149500e+02 1.797900e+02 +10 5440 4.952500e+02 -4.156801e+02 +12 5440 -4.695996e+01 -5.398300e+02 +7 5441 1.098730e+03 3.044900e+02 +9 5441 7.149500e+02 1.797900e+02 +10 5441 4.952500e+02 -4.156801e+02 +12 5441 -4.695996e+01 -5.398300e+02 +18 5441 1.702200e+02 -1.666003e+01 +20 5441 1.511400e+02 -2.101200e+02 +7 5442 1.200130e+03 3.110100e+02 +9 5442 8.322600e+02 1.874600e+02 +10 5442 5.771799e+02 -4.059500e+02 +12 5442 4.196997e+01 -5.354700e+02 +18 5442 2.403800e+02 -1.492004e+01 +20 5442 2.123300e+02 -2.072100e+02 +7 5443 1.200130e+03 3.110100e+02 +9 5443 8.322600e+02 1.874600e+02 +10 5443 5.771799e+02 -4.059500e+02 +18 5443 2.403800e+02 -1.492004e+01 +20 5443 2.123300e+02 -2.072100e+02 +7 5444 1.136530e+03 3.138700e+02 +9 5444 7.584299e+02 1.903600e+02 +10 5444 5.261899e+02 -4.050100e+02 +12 5444 -1.291003e+01 -5.319700e+02 +18 5444 1.980500e+02 -1.071997e+01 +7 5445 1.059930e+03 3.896899e+02 +9 5445 6.649099e+02 2.777600e+02 +10 5445 4.634700e+02 -3.409900e+02 +12 5445 -8.084998e+01 -4.642700e+02 +18 5445 1.444399e+02 4.347998e+01 +20 5445 1.256500e+02 -1.582800e+02 +7 5446 1.303520e+03 4.482000e+02 +10 5446 6.267000e+02 -2.905100e+02 +12 5446 1.237700e+02 -3.988199e+02 +18 5446 2.933300e+02 9.547998e+01 +7 5447 1.303520e+03 4.482000e+02 +10 5447 6.267000e+02 -2.905100e+02 +7 5448 -4.637100e+02 4.829299e+02 +9 5448 -1.366100e+03 4.219900e+02 +10 5448 -9.394900e+02 -2.458300e+02 +11 5448 -6.603500e+02 3.463300e+02 +14 5448 1.693200e+02 2.949200e+02 +16 5448 -7.856000e+01 4.368201e+02 +18 5448 -1.120350e+03 1.613201e+02 +19 5448 1.191960e+03 3.967200e+02 +7 5449 -1.200900e+02 5.816500e+02 +9 5449 -8.189100e+02 5.354299e+02 +10 5449 -5.848500e+02 -1.637900e+02 +11 5449 -1.452600e+02 4.543700e+02 +12 5449 -1.248730e+03 -2.383400e+02 +14 5449 3.775000e+02 3.627000e+02 +16 5449 1.541600e+02 5.206200e+02 +18 5449 -7.811400e+02 2.234500e+02 +20 5449 -6.674300e+02 -6.520020e+00 +7 5450 -3.496700e+02 5.826700e+02 +9 5450 -1.190490e+03 5.549600e+02 +11 5450 -4.990000e+02 4.735900e+02 +14 5450 2.368100e+02 3.511700e+02 +16 5450 -8.200073e-01 5.145000e+02 +18 5450 -1.009030e+03 2.432300e+02 +20 5450 -8.648800e+02 8.919983e+00 +7 5451 1.008780e+03 2.143700e+02 +9 5451 6.169900e+02 6.443005e+01 +12 5451 -1.265900e+02 -6.272200e+02 +20 5451 9.884998e+01 -2.695200e+02 +7 5452 1.166430e+03 2.415701e+02 +9 5452 7.963000e+02 1.051300e+02 +10 5452 5.541399e+02 -4.656300e+02 +12 5452 1.484998e+01 -6.007900e+02 +18 5452 2.180900e+02 -6.573999e+01 +20 5452 1.936400e+02 -2.504900e+02 +7 5453 2.657000e+02 3.008500e+02 +9 5453 -2.974200e+02 1.697500e+02 +10 5453 -2.250900e+02 -4.211700e+02 +11 5453 3.493199e+02 1.078100e+02 +12 5453 -8.479400e+02 -5.362700e+02 +18 5453 -4.597500e+02 -1.264001e+01 +20 5453 -3.895900e+02 -2.088800e+02 +7 5454 1.044310e+03 3.565701e+02 +9 5454 6.583501e+02 2.393201e+02 +10 5454 4.546101e+02 -3.689200e+02 +12 5454 -9.384998e+01 -4.943600e+02 +13 5454 1.389260e+03 5.081899e+02 +7 5455 -3.084900e+02 4.124900e+02 +9 5455 -1.109980e+03 3.204299e+02 +10 5455 -7.784400e+02 -3.143400e+02 +11 5455 -4.188600e+02 2.494200e+02 +14 5455 2.575600e+02 2.606800e+02 +16 5455 2.489001e+01 3.884600e+02 +18 5455 -9.675200e+02 9.137000e+01 +7 5456 -3.768600e+02 4.415300e+02 +9 5456 -1.220500e+03 3.594399e+02 +11 5456 -5.230900e+02 2.865900e+02 +14 5456 2.168200e+02 2.743900e+02 +16 5456 -2.184998e+01 4.081700e+02 +19 5456 1.296200e+03 3.570500e+02 +7 5457 -3.296100e+02 5.275500e+02 +9 5457 -1.164590e+03 4.779099e+02 +10 5457 -8.028800e+02 -2.096500e+02 +11 5457 -4.709800e+02 3.982100e+02 +18 5457 -9.934800e+02 1.934900e+02 +7 5458 -3.616300e+02 5.339700e+02 +10 5458 -8.320100e+02 -2.021500e+02 +14 5458 2.288300e+02 3.255000e+02 +16 5458 -8.789978e+00 4.777600e+02 +18 5458 -1.019210e+03 2.004600e+02 +19 5458 1.320570e+03 4.821599e+02 +7 5459 1.164130e+03 2.074099e+02 +10 5459 5.543501e+02 -4.938700e+02 +18 5459 2.164399e+02 -9.153003e+01 +20 5459 1.925100e+02 -2.726600e+02 +7 5460 1.164130e+03 2.074099e+02 +9 5460 7.950901e+02 6.273999e+01 +10 5460 5.543501e+02 -4.938700e+02 +12 5460 1.413000e+01 -6.312800e+02 +18 5460 2.164399e+02 -9.153003e+01 +20 5460 1.925100e+02 -2.726600e+02 +7 5461 1.322870e+03 2.117700e+02 +9 5461 9.537600e+02 8.019995e+01 +10 5461 6.619299e+02 -4.878700e+02 +18 5461 3.151000e+02 -8.351001e+01 +20 5461 2.761200e+02 -2.648000e+02 +7 5462 1.232930e+03 2.515300e+02 +9 5462 8.721201e+02 1.176300e+02 +18 5462 2.641200e+02 -5.994995e+01 +7 5463 1.166850e+03 2.973500e+02 +9 5463 7.936499e+02 1.709000e+02 +10 5463 5.512700e+02 -4.178800e+02 +12 5463 1.415002e+01 -5.477400e+02 +20 5463 1.922100e+02 -2.154000e+02 +7 5464 1.009530e+03 2.998800e+02 +9 5464 6.147600e+02 1.706599e+02 +10 5464 4.251201e+02 -4.179100e+02 +12 5464 -1.270500e+02 -5.467100e+02 +17 5464 -7.148199e+02 3.626500e+02 +18 5464 1.069000e+02 -2.321997e+01 +20 5464 9.841003e+01 -2.143600e+02 +7 5465 1.233180e+03 3.024299e+02 +9 5465 8.708101e+02 1.731500e+02 +10 5465 6.047600e+02 -4.130900e+02 +12 5465 7.305005e+01 -5.417500e+02 +20 5465 2.327200e+02 -2.144700e+02 +7 5466 1.233180e+03 3.024299e+02 +9 5466 8.708101e+02 1.731500e+02 +10 5466 6.047600e+02 -4.130900e+02 +12 5466 7.305005e+01 -5.417500e+02 +20 5466 2.327200e+02 -2.144700e+02 +7 5467 1.235350e+03 3.224099e+02 +9 5467 8.701499e+02 2.028000e+02 +10 5467 6.043601e+02 -3.948300e+02 +18 5467 2.648500e+02 -5.780029e+00 +20 5467 2.329600e+02 -1.997900e+02 +7 5468 1.235350e+03 3.224099e+02 +9 5468 8.701499e+02 2.028000e+02 +10 5468 6.043601e+02 -3.948300e+02 +18 5468 2.648500e+02 -5.780029e+00 +20 5468 2.329600e+02 -1.997900e+02 +7 5469 1.167340e+03 3.228000e+02 +9 5469 7.946001e+02 2.023101e+02 +10 5469 5.501101e+02 -3.955699e+02 +12 5469 1.372998e+01 -5.243700e+02 +18 5469 2.172900e+02 -4.869995e+00 +20 5469 1.925900e+02 -1.987600e+02 +7 5470 1.062710e+03 3.238000e+02 +9 5470 6.810500e+02 1.972900e+02 +10 5470 4.715601e+02 -4.000400e+02 +12 5470 -7.791003e+01 -5.247700e+02 +13 5470 1.460780e+03 3.750400e+02 +18 5470 1.478500e+02 -5.869995e+00 +20 5470 1.331899e+02 -2.003400e+02 +7 5471 1.213790e+03 3.531200e+02 +9 5471 8.454900e+02 2.380300e+02 +12 5471 5.210999e+01 -4.978000e+02 +18 5471 2.494600e+02 1.566003e+01 +7 5472 1.080770e+03 3.491899e+02 +9 5472 7.006399e+02 2.347600e+02 +12 5472 -6.577002e+01 -4.980500e+02 +13 5472 1.527440e+03 4.816699e+02 +17 5472 -5.488300e+02 4.781699e+02 +18 5472 1.589399e+02 1.632996e+01 +7 5473 1.263870e+03 3.538800e+02 +9 5473 9.043000e+02 2.386100e+02 +10 5473 6.272100e+02 -3.683700e+02 +12 5473 9.909998e+01 -4.967700e+02 +18 5473 2.852400e+02 1.531995e+01 +7 5474 2.459900e+02 3.558700e+02 +9 5474 -3.193800e+02 2.331599e+02 +10 5474 -2.408300e+02 -3.724100e+02 +18 5474 -4.722000e+02 2.772998e+01 +7 5475 1.279630e+03 3.802500e+02 +9 5475 9.213601e+02 2.697200e+02 +10 5475 6.375601e+02 -3.471200e+02 +12 5475 1.106700e+02 -4.729900e+02 +18 5475 2.951500e+02 3.475000e+01 +20 5475 2.583000e+02 -1.642200e+02 +7 5476 1.199030e+03 3.790300e+02 +9 5476 8.292300e+02 2.695801e+02 +10 5476 5.729399e+02 -3.471600e+02 +12 5476 4.055005e+01 -4.723500e+02 +18 5476 2.390699e+02 3.652002e+01 +20 5476 2.103600e+02 -1.635400e+02 +7 5477 1.137750e+03 3.773201e+02 +9 5477 7.575000e+02 2.662400e+02 +10 5477 5.236799e+02 -3.496400e+02 +12 5477 -1.335999e+01 -4.732000e+02 +18 5477 1.969900e+02 3.916003e+01 +20 5477 1.739500e+02 -1.646600e+02 +7 5478 -3.933101e+02 3.800100e+02 +9 5478 -1.242490e+03 2.793201e+02 +11 5478 -5.453100e+02 2.118400e+02 +14 5478 2.088000e+02 2.410700e+02 +7 5479 -4.875700e+02 3.898600e+02 +9 5479 -1.405600e+03 2.960400e+02 +10 5479 -9.660700e+02 -3.332200e+02 +11 5479 -6.996600e+02 2.278500e+02 +14 5479 1.545200e+02 2.440500e+02 +16 5479 -9.335999e+01 3.674000e+02 +18 5479 -1.148860e+03 8.379004e+01 +20 5479 -9.895300e+02 -1.276100e+02 +7 5480 1.062900e+03 3.988201e+02 +9 5480 6.771299e+02 2.907300e+02 +12 5480 -7.900000e+01 -4.540800e+02 +18 5480 1.467900e+02 5.047998e+01 +20 5480 1.313000e+02 -1.528000e+02 +7 5481 1.271710e+03 4.030100e+02 +9 5481 9.008899e+02 2.996599e+02 +10 5481 6.198301e+02 -3.288700e+02 +12 5481 9.505005e+01 -4.512900e+02 +18 5481 2.830800e+02 5.441992e+01 +7 5482 -3.527800e+02 4.050300e+02 +9 5482 -1.183400e+03 3.164099e+02 +10 5482 -8.251300e+02 -3.192700e+02 +11 5482 -4.890500e+02 2.451700e+02 +14 5482 2.309100e+02 2.571400e+02 +16 5482 -4.599976e+00 3.831700e+02 +18 5482 -1.008260e+03 9.056006e+01 +20 5482 -8.676000e+02 -1.195800e+02 +7 5483 -4.159200e+02 4.095701e+02 +9 5483 -1.284940e+03 3.183600e+02 +11 5483 -5.851900e+02 2.489300e+02 +14 5483 1.953400e+02 2.569600e+02 +16 5483 -4.601001e+01 3.846799e+02 +19 5483 1.251680e+03 3.112900e+02 +7 5484 -2.583199e+02 4.159500e+02 +9 5484 -1.025860e+03 3.234900e+02 +10 5484 -7.251899e+02 -3.117200e+02 +11 5484 -3.403400e+02 2.517000e+02 +18 5484 -9.127700e+02 9.317993e+01 +7 5485 -3.332100e+02 4.260200e+02 +9 5485 -1.147040e+03 3.363000e+02 +11 5485 -4.551900e+02 2.647900e+02 +14 5485 2.437400e+02 2.680200e+02 +16 5485 8.869995e+00 3.985500e+02 +18 5485 -9.867300e+02 1.039900e+02 +7 5486 4.626200e+02 4.484700e+02 +9 5486 3.471000e+02 2.238800e+02 +10 5486 2.055000e+02 -2.838700e+02 +12 5486 -5.076100e+02 -5.015000e+02 +13 5486 3.694399e+02 1.061010e+03 +16 5486 3.970100e+02 4.406200e+02 +17 5486 -1.761899e+02 7.776300e+02 +20 5486 -6.077002e+01 -1.852100e+02 +7 5487 -4.881800e+02 4.489399e+02 +9 5487 -1.406260e+03 3.786699e+02 +10 5487 -9.638500e+02 -2.777700e+02 +11 5487 -7.008700e+02 3.056700e+02 +14 5487 1.553900e+02 2.760200e+02 +16 5487 -9.365997e+01 4.109700e+02 +18 5487 -1.147780e+03 1.354399e+02 +19 5487 1.162530e+03 3.493401e+02 +20 5487 -9.877100e+02 -8.307996e+01 +7 5488 -3.917000e+02 4.638600e+02 +9 5488 -1.247670e+03 3.959500e+02 +10 5488 -8.623500e+02 -2.647300e+02 +11 5488 -5.422900e+02 3.138400e+02 +14 5488 2.101100e+02 2.874800e+02 +16 5488 -3.071002e+01 4.237200e+02 +19 5488 1.279750e+03 3.863900e+02 +7 5489 1.174530e+03 5.216400e+02 +9 5489 7.509900e+02 4.617100e+02 +18 5489 1.974800e+02 1.578600e+02 +20 5489 1.721700e+02 -6.090002e+01 +7 5490 1.174530e+03 5.216400e+02 +9 5490 7.509900e+02 4.617100e+02 +7 5491 1.065630e+03 5.208900e+02 +9 5491 6.183000e+02 4.645000e+02 +12 5491 -8.971997e+01 -3.221500e+02 +17 5491 -8.771300e+02 8.713000e+02 +20 5491 1.045000e+02 -6.138000e+01 +7 5492 1.081440e+03 5.408700e+02 +9 5492 6.387600e+02 4.874700e+02 +12 5492 -7.520996e+01 -3.028400e+02 +7 5493 1.081440e+03 5.408700e+02 +9 5493 6.387600e+02 4.874700e+02 +12 5493 -7.520996e+01 -3.028400e+02 +7 5494 -9.497998e+01 5.632500e+02 +9 5494 -7.987300e+02 5.075000e+02 +11 5494 -1.240100e+02 4.293000e+02 +16 5494 1.729500e+02 5.076500e+02 +18 5494 -7.680200e+02 2.064000e+02 +7 5495 -3.185601e+02 5.647200e+02 +9 5495 -1.153360e+03 5.268000e+02 +14 5495 2.533600e+02 3.419900e+02 +18 5495 -9.853500e+02 2.236699e+02 +20 5495 -8.453100e+02 -6.650024e+00 +7 5496 -3.808400e+02 5.755601e+02 +9 5496 -1.232750e+03 5.502300e+02 +10 5496 -8.513000e+02 -1.647500e+02 +11 5496 -5.402500e+02 4.661000e+02 +16 5496 -2.190002e+01 5.075000e+02 +20 5496 -8.897200e+02 6.400024e+00 +7 5497 -1.928800e+02 6.106500e+02 +9 5497 -9.324700e+02 5.807300e+02 +12 5497 -1.331670e+03 -2.031600e+02 +16 5497 1.037000e+02 5.406400e+02 +7 5498 -1.521801e+02 6.147000e+02 +11 5498 -1.928300e+02 4.996100e+02 +16 5498 1.321801e+02 5.446400e+02 +7 5499 -1.521801e+02 6.147000e+02 +11 5499 -1.928300e+02 4.996100e+02 +14 5499 3.589300e+02 3.797300e+02 +7 5500 -6.783997e+01 6.272700e+02 +9 5500 -7.657000e+02 5.955901e+02 +11 5500 -9.453003e+01 5.136700e+02 +12 5500 -1.195240e+03 -1.935900e+02 +14 5500 4.062000e+02 3.858500e+02 +16 5500 1.965100e+02 5.560200e+02 +18 5500 -7.467300e+02 2.597400e+02 +7 5501 -1.698500e+02 6.305200e+02 +9 5501 -9.025500e+02 6.028900e+02 +10 5501 -6.345900e+02 -1.180800e+02 +11 5501 -2.250600e+02 5.197500e+02 +12 5501 -1.306420e+03 -1.824200e+02 +14 5501 3.463400e+02 3.878900e+02 +16 5501 1.209399e+02 5.556200e+02 +18 5501 -8.302400e+02 2.669600e+02 +7 5502 5.821997e+01 9.840991e+01 +11 5502 7.202800e+02 -2.255500e+02 +12 5502 -8.445500e+02 -8.160601e+02 +16 5502 3.784998e+01 1.490100e+02 +7 5503 1.146460e+03 1.833600e+02 +9 5503 7.755801e+02 3.418005e+01 +10 5503 5.450200e+02 -5.145000e+02 +20 5503 1.834200e+02 -2.882700e+02 +7 5504 1.069150e+03 1.848401e+02 +9 5504 6.898000e+02 3.345996e+01 +10 5504 4.812600e+02 -5.146899e+02 +12 5504 -7.063000e+01 -6.554301e+02 +20 5504 1.371700e+02 -2.871300e+02 +7 5505 4.632900e+02 2.521400e+02 +9 5505 3.523500e+02 1.071997e+01 +10 5505 2.112900e+02 -4.622100e+02 +13 5505 3.765901e+02 2.550400e+02 +16 5505 4.004301e+02 2.799900e+02 +18 5505 -8.507996e+01 -1.181100e+02 +20 5505 -5.991003e+01 -2.994301e+02 +7 5506 2.022400e+02 2.883000e+02 +10 5506 -2.774800e+02 -4.332500e+02 +12 5506 -9.092500e+02 -5.520200e+02 +7 5507 1.325760e+03 2.899000e+02 +9 5507 9.530901e+02 1.771400e+02 +10 5507 6.592100e+02 -4.209000e+02 +12 5507 1.492000e+02 -5.480900e+02 +18 5507 3.165800e+02 -2.621997e+01 +20 5507 2.761600e+02 -2.140000e+02 +7 5508 1.165530e+03 2.973201e+02 +9 5508 7.936499e+02 1.709000e+02 +20 5508 1.893800e+02 -2.159900e+02 +7 5509 1.029520e+03 3.098800e+02 +9 5509 6.418601e+02 1.810500e+02 +12 5509 -1.081000e+02 -5.369900e+02 +7 5510 1.325100e+03 3.132400e+02 +9 5510 9.518799e+02 1.997100e+02 +10 5510 6.576101e+02 -4.019600e+02 +12 5510 1.482000e+02 -5.269301e+02 +18 5510 3.155000e+02 -9.119995e+00 +20 5510 2.754800e+02 -2.009100e+02 +7 5511 9.915100e+02 3.147600e+02 +9 5511 5.949099e+02 1.889700e+02 +12 5511 -1.417100e+02 -5.311200e+02 +18 5511 9.705005e+01 -1.021997e+01 +7 5512 1.123100e+03 3.526599e+02 +9 5512 7.430701e+02 2.379099e+02 +12 5512 -2.582996e+01 -4.961600e+02 +17 5512 -4.910800e+02 4.794099e+02 +20 5512 1.659000e+02 -1.797900e+02 +7 5513 2.230800e+02 3.797500e+02 +10 5513 -2.595200e+02 -3.511500e+02 +11 5513 3.084500e+02 2.018800e+02 +12 5513 -8.844800e+02 -4.596600e+02 +7 5514 1.119990e+03 3.916899e+02 +9 5514 7.351699e+02 2.824900e+02 +18 5514 1.854200e+02 4.656995e+01 +7 5515 1.063600e+02 3.926500e+02 +9 5515 -4.812400e+02 2.773000e+02 +11 5515 1.744500e+02 2.115000e+02 +7 5516 9.230701e+02 4.178900e+02 +10 5516 4.050601e+02 -3.148300e+02 +7 5517 1.047310e+03 4.222200e+02 +9 5517 6.595200e+02 3.187500e+02 +13 5517 1.395610e+03 7.603800e+02 +18 5517 1.355699e+02 6.928003e+01 +7 5518 1.047310e+03 4.222200e+02 +9 5518 6.595200e+02 3.187500e+02 +10 5518 4.529099e+02 -3.130400e+02 +12 5518 -9.455005e+01 -4.334000e+02 +13 5518 1.395610e+03 7.603800e+02 +20 5518 1.222300e+02 -1.363400e+02 +7 5519 1.063600e+03 4.403800e+02 +10 5519 4.655701e+02 -2.975100e+02 +18 5519 1.467800e+02 8.098999e+01 +7 5520 1.063600e+03 4.403800e+02 +9 5520 6.757500e+02 3.397200e+02 +10 5520 4.655701e+02 -2.975100e+02 +12 5520 -8.010999e+01 -4.160200e+02 +13 5520 1.449300e+03 8.274200e+02 +20 5520 1.309301e+02 -1.252900e+02 +7 5521 1.275710e+03 4.444900e+02 +10 5521 6.032000e+02 -2.942900e+02 +7 5522 -2.214000e+02 4.694299e+02 +9 5522 -9.662500e+02 3.887400e+02 +11 5522 -2.826600e+02 3.146700e+02 +18 5522 -8.751100e+02 1.353700e+02 +7 5523 -3.599301e+02 4.688201e+02 +10 5523 -8.295000e+02 -2.618600e+02 +16 5523 -9.599976e+00 4.291100e+02 +19 5523 1.319980e+03 3.978401e+02 +7 5524 -2.557000e+02 4.809399e+02 +9 5524 -1.024670e+03 4.110000e+02 +18 5524 -9.085900e+02 1.500400e+02 +7 5525 -4.962700e+02 4.824299e+02 +9 5525 -1.418810e+03 4.240801e+02 +11 5525 -7.132900e+02 3.479000e+02 +18 5525 -1.153620e+03 1.644700e+02 +20 5525 -9.928800e+02 -5.832996e+01 +7 5526 -3.105699e+02 4.857700e+02 +10 5526 -7.799400e+02 -2.481801e+02 +14 5526 2.585800e+02 3.024100e+02 +16 5526 2.351001e+01 4.426500e+02 +7 5527 -4.732400e+02 4.877100e+02 +9 5527 -1.392940e+03 4.271599e+02 +14 5527 1.603300e+02 2.966500e+02 +16 5527 -8.850000e+01 4.388800e+02 +20 5527 -9.787700e+02 -5.623999e+01 +7 5528 -5.501100e+02 4.895000e+02 +10 5528 -1.027300e+03 -2.382700e+02 +11 5528 -8.039300e+02 3.643500e+02 +16 5528 -1.345700e+02 4.390900e+02 +19 5528 1.090220e+03 3.918500e+02 +7 5529 -2.557900e+02 4.972300e+02 +9 5529 -1.024630e+03 4.249600e+02 +14 5529 2.916900e+02 3.100100e+02 +16 5529 5.900000e+01 4.547200e+02 +18 5529 -9.089400e+02 1.593401e+02 +7 5530 -8.338300e+02 5.103800e+02 +11 5530 -9.477300e+02 3.477500e+02 +18 5530 -1.342450e+03 1.664900e+02 +7 5531 1.086200e+03 5.183800e+02 +9 5531 6.452000e+02 4.603700e+02 +17 5531 -8.278700e+02 8.675000e+02 +20 5531 1.180400e+02 -6.313000e+01 +7 5532 -2.953700e+02 5.624900e+02 +9 5532 -1.120430e+03 5.306799e+02 +11 5532 -4.262600e+02 4.468300e+02 +14 5532 2.660400e+02 3.382700e+02 +16 5532 4.430005e+01 4.997600e+02 +7 5533 -2.762400e+02 5.663000e+02 +9 5533 -1.102210e+03 5.335300e+02 +12 5533 -1.446560e+03 -2.316400e+02 +14 5533 2.798200e+02 3.421200e+02 +16 5533 5.779004e+01 5.036500e+02 +18 5533 -9.459800e+02 2.290901e+02 +20 5533 -8.129700e+02 -1.750000e+00 +7 5534 -1.777000e+02 5.757000e+02 +9 5534 -9.036400e+02 5.341599e+02 +11 5534 -2.258700e+02 4.542800e+02 +14 5534 3.418900e+02 3.587800e+02 +16 5534 1.131500e+02 5.145400e+02 +18 5534 -8.305400e+02 2.228000e+02 +7 5535 -3.497100e+02 6.122600e+02 +9 5535 -1.218320e+03 6.011400e+02 +10 5535 -8.283900e+02 -1.303900e+02 +11 5535 -5.301200e+02 5.149800e+02 +16 5535 8.310059e+00 5.360100e+02 +18 5535 -1.025070e+03 2.700000e+02 +19 5535 1.354290e+03 5.769900e+02 +20 5535 -8.789900e+02 3.304004e+01 +7 5536 -1.546899e+02 6.149100e+02 +9 5536 -8.748200e+02 5.834099e+02 +10 5536 -6.190200e+02 -1.327100e+02 +11 5536 -2.033900e+02 5.014299e+02 +12 5536 -1.291590e+03 -2.007100e+02 +14 5536 3.531000e+02 3.800400e+02 +16 5536 1.261700e+02 5.428000e+02 +18 5536 -8.159000e+02 2.548101e+02 +20 5536 -6.992200e+02 2.004999e+01 +7 5537 -1.231600e+02 6.429100e+02 +10 5537 -5.853300e+02 -1.072100e+02 +11 5537 -1.513200e+02 5.330900e+02 +12 5537 -1.249180e+03 -1.733800e+02 +14 5537 3.769500e+02 3.971899e+02 +16 5537 1.523900e+02 5.666300e+02 +18 5537 -7.828300e+02 2.748201e+02 +20 5537 -6.693800e+02 3.745996e+01 +7 5538 1.114480e+03 1.582500e+02 +9 5538 7.520701e+02 3.050049e+00 +10 5538 5.262600e+02 -5.359100e+02 +7 5539 1.445400e+02 2.178301e+02 +10 5539 -3.275400e+02 -4.981899e+02 +7 5540 1.009660e+03 2.656200e+02 +9 5540 6.172600e+02 1.304299e+02 +10 5540 4.282600e+02 -4.466801e+02 +17 5540 -7.072100e+02 2.843000e+02 +18 5540 1.087900e+02 -4.763000e+01 +20 5540 9.959998e+01 -2.359200e+02 +7 5541 1.064650e+03 2.696400e+02 +9 5541 6.832700e+02 1.346899e+02 +12 5541 -7.792004e+01 -5.757400e+02 +13 5541 1.458500e+03 1.705000e+02 +17 5541 -5.843700e+02 2.901599e+02 +18 5541 1.460000e+02 -4.652002e+01 +7 5542 1.224400e+03 2.707800e+02 +9 5542 8.615801e+02 1.395300e+02 +10 5542 5.984500e+02 -4.388000e+02 +12 5542 6.406006e+01 -5.727400e+02 +18 5542 2.577200e+02 -4.567004e+01 +7 5543 1.066400e+03 2.940901e+02 +9 5543 6.844399e+02 1.669299e+02 +10 5543 4.745701e+02 -4.192500e+02 +12 5543 -7.462000e+01 -5.521600e+02 +13 5543 1.470080e+03 2.722100e+02 +17 5543 -5.815500e+02 3.486200e+02 +18 5543 1.498800e+02 -2.716003e+01 +7 5544 1.340120e+03 3.003600e+02 +9 5544 9.715000e+02 1.860500e+02 +10 5544 6.703301e+02 -4.121000e+02 +12 5544 1.620400e+02 -5.381000e+02 +18 5544 3.264900e+02 -1.843005e+01 +20 5544 2.855699e+02 -2.087400e+02 +7 5545 1.341110e+03 3.206699e+02 +9 5545 9.718000e+02 2.090400e+02 +12 5545 1.625100e+02 -5.194500e+02 +18 5545 3.273900e+02 -3.859985e+00 +7 5546 1.341110e+03 3.206699e+02 +9 5546 9.718000e+02 2.090400e+02 +10 5546 6.699199e+02 -3.953800e+02 +12 5546 1.625100e+02 -5.194500e+02 +18 5546 3.273900e+02 -3.859985e+00 +20 5546 2.862000e+02 -1.963600e+02 +7 5547 1.254210e+03 3.219700e+02 +9 5547 8.931899e+02 2.001300e+02 +10 5547 6.200000e+02 -3.953000e+02 +12 5547 8.980005e+01 -5.249301e+02 +18 5547 2.780601e+02 -7.729980e+00 +7 5548 1.351060e+03 3.332100e+02 +9 5548 9.825500e+02 2.240200e+02 +18 5548 3.335000e+02 4.800049e+00 +20 5548 2.914301e+02 -1.890300e+02 +7 5549 1.351060e+03 3.332100e+02 +9 5549 9.825500e+02 2.240200e+02 +10 5549 6.774199e+02 -3.852100e+02 +12 5549 1.708400e+02 -5.085601e+02 +18 5549 3.335000e+02 4.800049e+00 +20 5549 2.914301e+02 -1.890300e+02 +7 5550 1.089490e+03 3.677300e+02 +9 5550 7.060901e+02 2.547900e+02 +10 5550 4.846201e+02 -3.584900e+02 +12 5550 -5.801001e+01 -4.817900e+02 +13 5550 1.544590e+03 5.440801e+02 +17 5550 -5.552400e+02 5.159500e+02 +18 5550 1.627500e+02 2.760999e+01 +7 5551 1.167190e+03 3.694099e+02 +9 5551 7.931499e+02 2.574700e+02 +12 5551 1.270996e+01 -4.808500e+02 +18 5551 2.166700e+02 2.805005e+01 +7 5552 1.167190e+03 3.694099e+02 +9 5552 7.931499e+02 2.574700e+02 +12 5552 1.270996e+01 -4.808500e+02 +18 5552 2.166700e+02 2.805005e+01 +7 5553 -4.413700e+02 3.916799e+02 +9 5553 -1.329150e+03 2.997100e+02 +11 5553 -6.277900e+02 2.300500e+02 +16 5553 -6.278003e+01 3.696700e+02 +19 5553 1.218680e+03 2.832700e+02 +7 5554 1.145540e+03 3.973900e+02 +9 5554 7.661299e+02 2.896899e+02 +7 5555 1.009070e+03 4.207300e+02 +9 5555 6.137600e+02 3.177600e+02 +18 5555 1.070000e+02 6.700000e+01 +7 5556 -2.387000e+02 4.219500e+02 +9 5556 -9.958500e+02 3.280100e+02 +11 5556 -3.118000e+02 2.564300e+02 +18 5556 -8.921500e+02 9.798999e+01 +20 5556 -7.656000e+02 -1.157200e+02 +7 5557 -2.387000e+02 4.219500e+02 +9 5557 -9.958500e+02 3.280100e+02 +11 5557 -3.118000e+02 2.564300e+02 +18 5557 -8.921500e+02 9.798999e+01 +20 5557 -7.656000e+02 -1.157200e+02 +7 5558 -4.754000e+02 4.327300e+02 +9 5558 -1.384250e+03 3.544600e+02 +10 5558 -9.517100e+02 -2.934500e+02 +11 5558 -6.835900e+02 2.837200e+02 +14 5558 1.615500e+02 2.674100e+02 +16 5558 -8.466998e+01 3.994100e+02 +18 5558 -1.138090e+03 1.211799e+02 +19 5558 1.177470e+03 3.302400e+02 +20 5558 -9.790200e+02 -9.556006e+01 +7 5559 -4.419800e+02 4.387500e+02 +11 5559 -6.263200e+02 2.901900e+02 +7 5560 -2.401100e+02 4.438000e+02 +9 5560 -9.981900e+02 3.548600e+02 +7 5561 -2.401100e+02 4.438000e+02 +9 5561 -9.981900e+02 3.548600e+02 +11 5561 -3.152300e+02 2.837100e+02 +7 5562 -3.756300e+02 4.477900e+02 +9 5562 -1.215070e+03 3.699800e+02 +11 5562 -5.191300e+02 2.968700e+02 +14 5562 2.191600e+02 2.785900e+02 +16 5562 -1.857001e+01 4.129200e+02 +18 5562 -1.028450e+03 1.265601e+02 +19 5562 1.300490e+03 3.663500e+02 +7 5563 -4.271800e+02 4.511599e+02 +9 5563 -1.304730e+03 3.786500e+02 +10 5563 -8.992000e+02 -2.770000e+02 +11 5563 -6.048800e+02 3.044900e+02 +14 5563 1.899800e+02 2.789500e+02 +18 5563 -1.082410e+03 1.330000e+02 +19 5563 1.237570e+03 3.616699e+02 +20 5563 -9.321300e+02 -8.468994e+01 +7 5564 -2.268101e+02 4.835300e+02 +11 5564 -2.938100e+02 3.347400e+02 +18 5564 -8.792000e+02 1.479099e+02 +7 5565 1.514500e+02 4.905701e+02 +10 5565 -3.215500e+02 -2.504000e+02 +12 5565 -9.548500e+02 -3.486300e+02 +7 5566 4.238600e+02 4.991200e+02 +10 5566 1.748300e+02 -2.393101e+02 +18 5566 -1.050000e+02 4.700000e+01 +7 5567 1.008730e+03 5.132100e+02 +9 5567 5.505500e+02 4.545601e+02 +12 5567 -1.421801e+02 -3.268101e+02 +17 5567 -1.005030e+03 8.606799e+02 +7 5568 1.008730e+03 5.132100e+02 +9 5568 5.505500e+02 4.545601e+02 +12 5568 -1.421801e+02 -3.268101e+02 +7 5569 -1.229004e+01 5.133800e+02 +11 5569 2.073999e+01 3.630701e+02 +16 5569 2.256300e+02 4.743300e+02 +7 5570 -1.229004e+01 5.133800e+02 +11 5570 2.073999e+01 3.630701e+02 +16 5570 2.256300e+02 4.743300e+02 +7 5571 -5.226200e+02 5.167800e+02 +10 5571 -9.969200e+02 -2.151400e+02 +7 5572 1.008570e+03 5.265300e+02 +9 5572 5.500400e+02 4.712600e+02 +12 5572 -1.428600e+02 -3.136600e+02 +17 5572 -1.005110e+03 8.935400e+02 +20 5572 6.880005e+01 -5.435999e+01 +7 5573 -3.476899e+02 5.326500e+02 +9 5573 -1.191860e+03 4.875500e+02 +18 5573 -1.005260e+03 1.997200e+02 +7 5574 1.194610e+03 5.405701e+02 +10 5574 5.263000e+02 -2.156600e+02 +12 5574 2.504004e+01 -3.045800e+02 +18 5574 2.086500e+02 1.694299e+02 +20 5574 1.850000e+02 -5.034998e+01 +7 5575 -2.478700e+02 5.659700e+02 +9 5575 -1.058640e+03 5.340300e+02 +11 5575 -3.779600e+02 4.508400e+02 +16 5575 7.908997e+01 5.042400e+02 +18 5575 -9.258800e+02 2.268401e+02 +7 5576 -4.225800e+02 5.654800e+02 +10 5576 -8.947300e+02 -1.724000e+02 +16 5576 -4.912000e+01 4.980601e+02 +19 5576 1.247170e+03 5.058600e+02 +7 5577 -1.652000e+02 5.995000e+02 +10 5577 -6.287300e+02 -1.468600e+02 +11 5577 -2.115400e+02 4.785300e+02 +12 5577 -1.299420e+03 -2.156899e+02 +14 5577 3.493600e+02 3.715300e+02 +18 5577 -8.224900e+02 2.401100e+02 +20 5577 -7.028000e+02 8.140015e+00 +7 5578 -1.297000e+02 6.127000e+02 +9 5578 -8.283800e+02 5.721599e+02 +11 5578 -1.571200e+02 4.902300e+02 +7 5579 -4.670200e+02 6.616100e+02 +9 5579 -1.386430e+03 6.789100e+02 +14 5579 1.717000e+02 3.882300e+02 +16 5579 -7.867999e+01 5.659000e+02 +7 5580 -4.315400e+02 6.643800e+02 +11 5580 -6.460700e+02 5.869301e+02 +16 5580 -5.146002e+01 5.711700e+02 +7 5581 1.078300e+03 1.465200e+02 +9 5581 7.020200e+02 -1.097998e+01 +7 5582 1.102070e+03 1.705701e+02 +9 5582 7.413101e+02 1.842004e+01 +10 5582 5.177800e+02 -5.255800e+02 +20 5582 1.635100e+02 -2.961700e+02 +7 5583 1.519800e+02 1.812200e+02 +10 5583 -3.184399e+02 -5.308600e+02 +11 5583 2.337500e+02 -4.129999e+01 +12 5583 -9.585800e+02 -6.590400e+02 +18 5583 -5.404600e+02 -1.082500e+02 +20 5583 -4.598900e+02 -2.923199e+02 +7 5584 1.340250e+03 1.981599e+02 +9 5584 9.755801e+02 6.329004e+01 +10 5584 6.763301e+02 -4.973400e+02 +12 5584 1.656100e+02 -6.321300e+02 +18 5584 3.284500e+02 -9.368994e+01 +20 5584 2.880000e+02 -2.731100e+02 +7 5585 1.339590e+03 2.197900e+02 +9 5585 9.734800e+02 8.915002e+01 +10 5585 6.745701e+02 -4.795300e+02 +12 5585 1.637100e+02 -6.122100e+02 +18 5585 3.272200e+02 -7.693005e+01 +20 5585 2.868400e+02 -2.594700e+02 +7 5586 1.164200e+03 2.213700e+02 +9 5586 7.940601e+02 8.075000e+01 +10 5586 5.521299e+02 -4.816700e+02 +18 5586 2.168400e+02 -8.023999e+01 +20 5586 1.927100e+02 -2.628000e+02 +7 5587 1.340270e+03 2.395901e+02 +10 5587 6.740200e+02 -4.623800e+02 +12 5587 1.637100e+02 -5.941400e+02 +7 5588 1.157110e+03 2.445801e+02 +9 5588 7.840500e+02 1.079301e+02 +12 5588 6.280029e+00 -5.971801e+02 +18 5588 2.103300e+02 -6.303003e+01 +20 5588 1.871899e+02 -2.485200e+02 +7 5589 4.420000e+02 2.475500e+02 +9 5589 3.278400e+02 4.390015e+00 +10 5589 1.917100e+02 -4.662900e+02 +13 5589 2.830200e+02 2.390000e+02 +16 5589 3.833199e+02 2.765601e+02 +17 5589 -2.192200e+02 2.552500e+02 +18 5589 -9.981995e+01 -1.208900e+02 +7 5590 1.254190e+03 2.705400e+02 +9 5590 8.973401e+02 1.402400e+02 +7 5591 1.190940e+03 2.710000e+02 +9 5591 8.253601e+02 1.398700e+02 +10 5591 5.746399e+02 -4.393000e+02 +12 5591 3.875000e+01 -5.725400e+02 +7 5592 1.022300e+03 2.717400e+02 +9 5592 6.315601e+02 1.375801e+02 +17 5592 -6.853600e+02 2.999500e+02 +18 5592 1.180200e+02 -4.416003e+01 +20 5592 1.069000e+02 -2.319600e+02 +7 5593 5.817400e+02 2.709600e+02 +9 5593 4.808900e+02 3.054004e+01 +16 5593 4.943800e+02 2.976100e+02 +7 5594 9.803301e+02 3.279000e+02 +9 5594 5.815801e+02 2.048401e+02 +10 5594 4.010801e+02 -3.936500e+02 +12 5594 -1.530400e+02 -5.196000e+02 +17 5594 -7.745800e+02 4.312200e+02 +18 5594 8.716003e+01 -1.369995e+00 +20 5594 8.144995e+01 -1.960200e+02 +7 5595 1.105900e+02 3.334700e+02 +10 5595 -3.576801e+02 -3.886100e+02 +11 5595 1.798199e+02 1.399100e+02 +12 5595 -1.000180e+03 -5.049200e+02 +7 5596 1.341640e+03 3.540400e+02 +9 5596 9.720801e+02 2.488500e+02 +18 5596 3.279500e+02 2.058997e+01 +20 5596 2.861600e+02 -1.755699e+02 +7 5597 1.341640e+03 3.540400e+02 +9 5597 9.720801e+02 2.488500e+02 +10 5597 6.688799e+02 -3.679000e+02 +12 5597 1.628900e+02 -4.886600e+02 +18 5597 3.279500e+02 2.058997e+01 +20 5597 2.861600e+02 -1.755699e+02 +7 5598 1.117080e+03 3.670400e+02 +9 5598 7.358301e+02 2.543500e+02 +7 5599 1.098110e+03 3.906000e+02 +9 5599 7.166799e+02 2.834700e+02 +10 5599 4.933501e+02 -3.389000e+02 +12 5599 -5.083997e+01 -4.601899e+02 +7 5600 3.414600e+02 3.973201e+02 +10 5600 -1.700300e+02 -3.356899e+02 +11 5600 4.111801e+02 2.303200e+02 +12 5600 -7.781800e+02 -4.363300e+02 +20 5600 -3.489800e+02 -1.408300e+02 +7 5601 -4.545600e+02 3.962200e+02 +9 5601 -1.351110e+03 3.061000e+02 +11 5601 -6.481900e+02 2.362100e+02 +14 5601 1.725800e+02 2.483600e+02 +16 5601 -7.112000e+01 3.736000e+02 +7 5602 1.080040e+03 4.003301e+02 +9 5602 6.935300e+02 2.914900e+02 +10 5602 4.782300e+02 -3.334100e+02 +12 5602 -6.481995e+01 -4.511000e+02 +13 5602 1.501930e+03 6.593700e+02 +18 5602 1.564900e+02 5.058997e+01 +20 5602 1.400601e+02 -1.502400e+02 +7 5603 3.013700e+02 4.168900e+02 +9 5603 -2.673000e+02 3.200100e+02 +12 5603 -8.125800e+02 -4.182700e+02 +7 5604 -4.563200e+02 4.166400e+02 +9 5604 -1.353580e+03 3.314399e+02 +11 5604 -6.506600e+02 2.603200e+02 +14 5604 1.724600e+02 2.585800e+02 +16 5604 -7.260999e+01 3.888300e+02 +19 5604 1.200210e+03 3.117800e+02 +7 5605 -4.855500e+02 4.204700e+02 +9 5605 -1.400520e+03 3.390801e+02 +10 5605 -9.622900e+02 -3.044600e+02 +11 5605 -6.948200e+02 2.682000e+02 +14 5605 1.560800e+02 2.606200e+02 +16 5605 -9.303998e+01 3.902700e+02 +19 5605 1.164250e+03 3.135200e+02 +20 5605 -9.852400e+02 -1.046500e+02 +7 5606 -3.735601e+02 4.263000e+02 +9 5606 -1.213540e+03 3.401000e+02 +10 5606 -8.445600e+02 -3.016200e+02 +11 5606 -5.175900e+02 2.679900e+02 +16 5606 -1.858002e+01 3.974700e+02 +19 5606 1.302230e+03 3.383700e+02 +7 5607 2.033800e+02 4.515300e+02 +10 5607 -2.759100e+02 -2.856300e+02 +11 5607 2.855601e+02 2.869500e+02 +7 5608 1.019720e+03 4.714900e+02 +9 5608 5.659600e+02 4.014800e+02 +20 5608 7.656006e+01 -9.101001e+01 +7 5609 4.520500e+02 4.890801e+02 +9 5609 3.382600e+02 2.642300e+02 +12 5609 -5.178400e+02 -4.697900e+02 +16 5609 3.856801e+02 4.741100e+02 +17 5609 -1.830800e+02 8.846799e+02 +18 5609 -9.032996e+01 4.030005e+01 +7 5610 4.377700e+02 4.888800e+02 +9 5610 3.234900e+02 2.654299e+02 +10 5610 1.840500e+02 -2.485699e+02 +12 5610 -5.295000e+02 -4.685601e+02 +16 5610 3.748101e+02 4.735400e+02 +17 5610 -2.169100e+02 8.883501e+02 +18 5610 -9.965002e+01 4.072998e+01 +20 5610 -7.331006e+01 -1.625601e+02 +7 5611 -5.692900e+02 5.319399e+02 +10 5611 -1.045480e+03 -1.985699e+02 +11 5611 -8.393800e+02 4.187700e+02 +14 5611 1.128200e+02 3.179800e+02 +18 5611 -1.234830e+03 2.117100e+02 +20 5611 -1.061110e+03 -1.595001e+01 +7 5612 -5.453500e+02 5.357600e+02 +9 5612 -1.505350e+03 5.023700e+02 +10 5612 -1.020110e+03 -1.958800e+02 +11 5612 -7.991600e+02 4.220300e+02 +14 5612 1.258400e+02 3.208300e+02 +16 5612 -1.317500e+02 4.725200e+02 +18 5612 -1.208150e+03 2.134800e+02 +19 5612 1.096340e+03 4.484000e+02 +20 5612 -1.039440e+03 -1.490997e+01 +7 5613 -5.095400e+02 5.418900e+02 +10 5613 -9.825300e+02 -1.911100e+02 +11 5613 -7.418000e+02 4.267000e+02 +16 5613 -1.084100e+02 4.783500e+02 +18 5613 -1.170980e+03 2.156899e+02 +19 5613 1.136230e+03 4.631200e+02 +7 5614 -3.669500e+02 5.432500e+02 +10 5614 -8.372800e+02 -1.928700e+02 +7 5615 -3.669500e+02 5.432500e+02 +10 5615 -8.372800e+02 -1.928700e+02 +11 5615 -5.181400e+02 4.188700e+02 +14 5615 2.261200e+02 3.300500e+02 +16 5615 -1.269000e+01 4.842900e+02 +19 5615 1.315780e+03 4.908000e+02 +20 5615 -8.779200e+02 -2.103003e+01 +7 5616 -2.610200e+02 5.584500e+02 +10 5616 -7.396900e+02 -1.807300e+02 +11 5616 -3.928700e+02 4.428000e+02 +12 5616 -1.432110e+03 -2.410100e+02 +16 5616 6.843994e+01 5.001200e+02 +18 5616 -9.364000e+02 2.202800e+02 +20 5616 -8.026500e+02 -9.530029e+00 +7 5617 -2.610200e+02 5.584500e+02 +9 5617 -1.076410e+03 5.234399e+02 +10 5617 -7.396900e+02 -1.807300e+02 +12 5617 -1.432110e+03 -2.410100e+02 +14 5617 2.854700e+02 3.387900e+02 +16 5617 6.843994e+01 5.001200e+02 +18 5617 -9.364000e+02 2.202800e+02 +20 5617 -8.026500e+02 -9.530029e+00 +7 5618 -7.743005e+01 5.800000e+02 +9 5618 -7.715300e+02 5.304399e+02 +10 5618 -5.486200e+02 -1.671200e+02 +11 5618 -1.020700e+02 4.497100e+02 +14 5618 4.013500e+02 3.616100e+02 +16 5618 1.889399e+02 5.219500e+02 +7 5619 -2.700000e+01 5.973300e+02 +9 5619 -7.111400e+02 5.543700e+02 +10 5619 -5.038101e+02 -1.518500e+02 +11 5619 -4.613000e+01 4.748400e+02 +12 5619 -1.153650e+03 -2.250601e+02 +14 5619 4.292600e+02 3.697800e+02 +16 5619 2.301100e+02 5.359900e+02 +18 5619 -7.106200e+02 2.344399e+02 +7 5620 5.870100e+02 6.398800e+02 +10 5620 2.882700e+02 -1.181700e+02 +7 5621 -4.456900e+02 6.600400e+02 +9 5621 -1.359280e+03 6.680500e+02 +11 5621 -6.620400e+02 5.797000e+02 +16 5621 -6.204999e+01 5.677800e+02 +20 5621 -9.548400e+02 7.552002e+01 +7 5622 2.014001e+01 1.508700e+02 +9 5622 -5.784998e+01 -1.209700e+02 +11 5622 6.802900e+02 -1.688700e+02 +16 5622 7.719971e+00 1.912100e+02 +18 5622 -3.493500e+02 -1.971300e+02 +7 5623 1.758700e+02 1.672100e+02 +11 5623 2.592500e+02 -6.295001e+01 +12 5623 -9.377100e+02 -6.765200e+02 +7 5624 3.031500e+02 1.675500e+02 +9 5624 -2.592800e+02 1.119995e+00 +10 5624 -1.947200e+02 -5.429900e+02 +11 5624 3.842800e+02 -5.425000e+01 +13 5624 -1.576560e+03 -1.981000e+02 +18 5624 -4.375699e+02 -1.179800e+02 +20 5624 -3.702800e+02 -2.995200e+02 +7 5625 4.422700e+02 1.916400e+02 +9 5625 3.355100e+02 -5.594995e+01 +13 5625 3.079500e+02 1.046997e+01 +16 5625 3.803400e+02 2.308100e+02 +7 5626 1.349500e+03 1.924299e+02 +9 5626 9.842400e+02 5.882996e+01 +10 5626 6.839500e+02 -5.025601e+02 +12 5626 1.730601e+02 -6.363300e+02 +18 5626 3.339200e+02 -9.780005e+01 +20 5626 2.927800e+02 -2.763500e+02 +7 5627 1.053040e+03 1.964800e+02 +10 5627 4.681201e+02 -5.041200e+02 +12 5627 -8.494995e+01 -6.431600e+02 +18 5627 1.406600e+02 -9.956006e+01 +7 5628 1.420000e+02 2.249199e+02 +9 5628 -4.366700e+02 6.512000e+01 +10 5628 -3.294200e+02 -4.928900e+02 +12 5628 -9.708600e+02 -6.179900e+02 +7 5629 1.155990e+03 2.290000e+02 +9 5629 7.830801e+02 8.988000e+01 +10 5629 5.452500e+02 -4.751899e+02 +12 5629 5.349976e+00 -6.111000e+02 +18 5629 2.096700e+02 -7.509998e+01 +20 5629 1.864700e+02 -2.582600e+02 +7 5630 4.404700e+02 2.292400e+02 +9 5630 3.273000e+02 -1.340002e+01 +10 5630 1.905800e+02 -4.827600e+02 +12 5630 -5.307800e+02 -6.890300e+02 +13 5630 2.772900e+02 1.650500e+02 +16 5630 3.825000e+02 2.623500e+02 +17 5630 -2.216400e+02 2.061100e+02 +18 5630 -1.006300e+02 -1.333900e+02 +20 5630 -7.306995e+01 -3.120601e+02 +7 5631 4.404700e+02 2.292400e+02 +9 5631 3.273000e+02 -1.340002e+01 +10 5631 1.905800e+02 -4.827600e+02 +12 5631 -5.307800e+02 -6.890300e+02 +13 5631 2.772900e+02 1.650500e+02 +16 5631 3.825000e+02 2.623500e+02 +17 5631 -2.216400e+02 2.061100e+02 +18 5631 -1.006300e+02 -1.333900e+02 +20 5631 -7.306995e+01 -3.120601e+02 +7 5632 4.887400e+02 2.409000e+02 +10 5632 2.346400e+02 -4.733101e+02 +13 5632 4.839399e+02 2.054099e+02 +16 5632 4.201000e+02 2.710701e+02 +20 5632 -4.420996e+01 -3.061300e+02 +7 5633 1.215850e+03 2.604299e+02 +9 5633 8.540200e+02 1.277500e+02 +10 5633 5.937800e+02 -4.478000e+02 +18 5633 2.515400e+02 -5.217004e+01 +20 5633 2.238900e+02 -2.386700e+02 +7 5634 1.250720e+03 2.610300e+02 +9 5634 8.929900e+02 1.286899e+02 +12 5634 8.833997e+01 -5.813300e+02 +18 5634 2.771200e+02 -5.180005e+01 +7 5635 1.150580e+03 2.622700e+02 +9 5635 7.775701e+02 1.294700e+02 +10 5635 5.408201e+02 -4.467200e+02 +12 5635 1.099976e+00 -5.794000e+02 +18 5635 2.064800e+02 -5.035999e+01 +20 5635 1.839100e+02 -2.369800e+02 +7 5636 4.717000e+02 2.730901e+02 +9 5636 3.579600e+02 3.477002e+01 +13 5636 4.029099e+02 3.443301e+02 +16 5636 4.068300e+02 2.977400e+02 +18 5636 -8.043994e+01 -1.039700e+02 +7 5637 1.342120e+03 2.802100e+02 +10 5637 6.736599e+02 -4.291000e+02 +12 5637 1.654200e+02 -5.573000e+02 +20 5637 2.881100e+02 -2.221899e+02 +7 5638 1.015700e+03 2.924700e+02 +9 5638 6.233899e+02 1.615100e+02 +12 5638 -1.208800e+02 -5.527800e+02 +20 5638 1.027200e+02 -2.185400e+02 +7 5639 3.696200e+02 3.280400e+02 +10 5639 -1.494500e+02 -3.989000e+02 +7 5640 1.257890e+03 3.425000e+02 +9 5640 8.983701e+02 2.260000e+02 +12 5640 9.273999e+01 -5.066600e+02 +18 5640 2.809100e+02 7.339966e+00 +7 5641 1.263940e+03 3.511699e+02 +9 5641 9.053601e+02 2.364000e+02 +10 5641 6.271599e+02 -3.708199e+02 +12 5641 9.806006e+01 -4.988700e+02 +18 5641 2.852000e+02 1.323999e+01 +20 5641 2.504399e+02 -1.822400e+02 +7 5642 1.040420e+03 3.698101e+02 +9 5642 6.520901e+02 2.554500e+02 +10 5642 4.493999e+02 -3.569500e+02 +13 5642 1.369260e+03 5.601000e+02 +17 5642 -6.417600e+02 5.238401e+02 +20 5642 1.178900e+02 -1.695400e+02 +7 5643 1.080620e+03 3.780500e+02 +10 5643 4.796699e+02 -3.510300e+02 +12 5643 -6.392004e+01 -4.720200e+02 +20 5643 1.404301e+02 -1.636700e+02 +7 5644 1.230080e+03 3.939800e+02 +9 5644 8.638799e+02 2.865400e+02 +10 5644 5.962800e+02 -3.358800e+02 +12 5644 6.944995e+01 -4.591200e+02 +7 5645 1.161600e+03 3.936100e+02 +10 5645 5.417300e+02 -3.360200e+02 +12 5645 1.006006e+01 -4.589900e+02 +7 5646 -3.643199e+02 4.251799e+02 +9 5646 -1.198010e+03 3.372500e+02 +11 5646 -5.025000e+02 2.657700e+02 +14 5646 2.254700e+02 2.661100e+02 +16 5646 -1.209998e+01 3.972200e+02 +19 5646 1.314880e+03 3.386799e+02 +20 5646 -8.748400e+02 -1.080100e+02 +7 5647 -3.137100e+02 4.322900e+02 +9 5647 -1.116090e+03 3.460000e+02 +11 5647 -4.258300e+02 2.727600e+02 +14 5647 2.550400e+02 2.714200e+02 +7 5648 -4.635500e+02 4.453000e+02 +9 5648 -1.365680e+03 3.720701e+02 +10 5648 -9.382000e+02 -2.817700e+02 +11 5648 -6.621300e+02 2.984600e+02 +14 5648 1.690100e+02 2.746900e+02 +16 5648 -7.716998e+01 4.088800e+02 +18 5648 -1.121310e+03 1.306799e+02 +19 5648 1.191750e+03 3.482700e+02 +20 5648 -9.650600e+02 -8.716003e+01 +7 5649 4.415400e+02 4.465601e+02 +9 5649 3.244000e+02 2.210000e+02 +10 5649 1.857200e+02 -2.858500e+02 +12 5649 -5.279300e+02 -5.033000e+02 +13 5649 2.834100e+02 1.060610e+03 +16 5649 3.807100e+02 4.397800e+02 +17 5649 -2.280800e+02 7.811899e+02 +18 5649 -9.968005e+01 1.351001e+01 +20 5649 -7.284998e+01 -1.866100e+02 +7 5650 4.415400e+02 4.465601e+02 +9 5650 3.244000e+02 2.210000e+02 +10 5650 1.857200e+02 -2.858500e+02 +12 5650 -5.279300e+02 -5.033000e+02 +13 5650 2.834100e+02 1.060610e+03 +16 5650 3.807100e+02 4.397800e+02 +17 5650 -2.280800e+02 7.811899e+02 +18 5650 -9.968005e+01 1.351001e+01 +20 5650 -7.284998e+01 -1.866100e+02 +7 5651 -4.564400e+02 4.525300e+02 +9 5651 -1.354680e+03 3.840601e+02 +10 5651 -9.309800e+02 -2.738300e+02 +11 5651 -6.512600e+02 3.090300e+02 +14 5651 1.726500e+02 2.819200e+02 +16 5651 -7.340002e+01 4.173500e+02 +19 5651 1.199400e+03 3.625300e+02 +20 5651 -9.588500e+02 -8.055005e+01 +7 5652 -4.564400e+02 4.525300e+02 +9 5652 -1.354920e+03 3.852000e+02 +10 5652 -9.310000e+02 -2.730800e+02 +11 5652 -6.512600e+02 3.090300e+02 +14 5652 1.726500e+02 2.819200e+02 +16 5652 -7.340002e+01 4.173500e+02 +19 5652 1.199400e+03 3.625300e+02 +20 5652 -9.588500e+02 -8.055005e+01 +7 5653 -4.248000e+02 4.640901e+02 +9 5653 -1.299860e+03 3.959199e+02 +7 5654 -3.734100e+02 4.710000e+02 +9 5654 -1.215230e+03 3.973700e+02 +10 5654 -8.434300e+02 -2.644600e+02 +11 5654 -5.190300e+02 3.225300e+02 +14 5654 2.208700e+02 2.912900e+02 +16 5654 -1.847998e+01 4.297500e+02 +19 5654 1.302740e+03 3.959800e+02 +7 5655 -3.075300e+02 4.731500e+02 +9 5655 -1.110680e+03 4.006300e+02 +11 5655 -4.200000e+02 3.254400e+02 +7 5656 -3.465100e+02 4.735701e+02 +9 5656 -1.171130e+03 4.039299e+02 +16 5656 -1.090027e+00 4.337100e+02 +7 5657 -3.465100e+02 4.735701e+02 +9 5657 -1.172210e+03 4.071300e+02 +14 5657 2.367000e+02 2.941800e+02 +16 5657 -1.090027e+00 4.337100e+02 +19 5657 1.336440e+03 4.066799e+02 +7 5658 -4.580800e+02 4.736100e+02 +9 5658 -1.355720e+03 4.083301e+02 +11 5658 -6.523900e+02 3.322200e+02 +14 5658 1.722600e+02 2.905700e+02 +16 5658 -7.427002e+01 4.303700e+02 +19 5658 1.198510e+03 3.852900e+02 +20 5658 -9.589300e+02 -6.797998e+01 +7 5659 -2.714200e+02 4.840701e+02 +9 5659 -1.048480e+03 4.134700e+02 +10 5659 -7.371600e+02 -2.491500e+02 +11 5659 -3.609700e+02 3.396900e+02 +14 5659 2.818300e+02 3.021800e+02 +16 5659 4.897998e+01 4.434600e+02 +18 5659 -9.243400e+02 1.507700e+02 +20 5659 -7.920100e+02 -6.854004e+01 +7 5660 -3.738700e+02 4.860901e+02 +9 5660 -1.215920e+03 4.188800e+02 +10 5660 -8.438200e+02 -2.465601e+02 +11 5660 -5.197600e+02 3.436100e+02 +16 5660 -1.928003e+01 4.418900e+02 +18 5660 -1.027470e+03 1.585100e+02 +20 5660 -8.824400e+02 -6.351001e+01 +7 5661 -4.176400e+02 4.867900e+02 +9 5661 -1.287160e+03 4.220200e+02 +11 5661 -5.888600e+02 3.452300e+02 +14 5661 1.955800e+02 2.985400e+02 +16 5661 -4.734998e+01 4.401600e+02 +18 5661 -1.072310e+03 1.616799e+02 +19 5661 1.247870e+03 4.078700e+02 +7 5662 -3.321300e+02 4.968000e+02 +9 5662 -1.148170e+03 4.328401e+02 +10 5662 -8.001400e+02 -2.368900e+02 +11 5662 -4.556100e+02 3.558300e+02 +16 5662 8.530029e+00 4.506200e+02 +18 5662 -9.849500e+02 1.652300e+02 +19 5662 1.355880e+03 4.395100e+02 +20 5662 -8.455000e+02 -5.740002e+01 +7 5663 -3.229900e+02 5.003000e+02 +10 5663 -7.903100e+02 -2.345400e+02 +16 5663 1.477002e+01 4.527800e+02 +7 5664 1.185080e+03 5.050500e+02 +9 5664 7.616499e+02 4.427300e+02 +10 5664 5.190801e+02 -2.448900e+02 +12 5664 1.806995e+01 -3.380200e+02 +17 5664 -6.178600e+02 8.184100e+02 +7 5665 -2.426899e+02 5.065500e+02 +9 5665 -1.002520e+03 4.389199e+02 +11 5665 -3.179300e+02 3.625200e+02 +7 5666 -2.426899e+02 5.065500e+02 +9 5666 -1.002520e+03 4.389199e+02 +11 5666 -3.179300e+02 3.625200e+02 +7 5667 -2.471997e+01 5.098101e+02 +10 5667 -4.858000e+02 -2.292800e+02 +12 5667 -1.138620e+03 -3.219800e+02 +18 5667 -6.870900e+02 1.564900e+02 +7 5668 1.182150e+03 5.365200e+02 +9 5668 7.580901e+02 4.803800e+02 +7 5669 -7.954400e+02 5.417500e+02 +10 5669 -1.198010e+03 -1.820500e+02 +11 5669 -9.102400e+02 3.876799e+02 +18 5669 -1.314990e+03 1.917700e+02 +20 5669 -1.129140e+03 -3.529004e+01 +7 5670 -3.142600e+02 5.434900e+02 +10 5670 -7.891300e+02 -1.947000e+02 +16 5670 2.581006e+01 4.855000e+02 +7 5671 1.108430e+03 5.492500e+02 +9 5671 6.703301e+02 4.973500e+02 +12 5671 -5.113000e+01 -2.957000e+02 +18 5671 1.486100e+02 1.764800e+02 +20 5671 1.320400e+02 -4.330005e+01 +7 5672 1.108430e+03 5.492500e+02 +9 5672 6.703301e+02 4.973500e+02 +12 5672 -5.113000e+01 -2.957000e+02 +18 5672 1.486100e+02 1.764800e+02 +20 5672 1.320400e+02 -4.330005e+01 +7 5673 2.068101e+02 5.512500e+02 +10 5673 -2.736400e+02 -1.969000e+02 +7 5674 5.030699e+02 5.799800e+02 +10 5674 2.360400e+02 -1.682700e+02 +16 5674 4.295200e+02 5.502800e+02 +7 5675 -4.175300e+02 5.970601e+02 +9 5675 -1.310630e+03 5.814700e+02 +10 5675 -8.915400e+02 -1.436400e+02 +11 5675 -6.139000e+02 4.965800e+02 +14 5675 1.971600e+02 3.557000e+02 +18 5675 -1.083300e+03 2.604600e+02 +20 5675 -9.291200e+02 2.483008e+01 +7 5676 -1.784500e+02 6.137300e+02 +9 5676 -9.140500e+02 5.816400e+02 +10 5676 -6.435000e+02 -1.343300e+02 +11 5676 -2.359000e+02 4.977300e+02 +12 5676 -1.315750e+03 -1.995699e+02 +14 5676 3.406900e+02 3.782600e+02 +16 5676 1.142400e+02 5.412600e+02 +18 5676 -8.370400e+02 2.529299e+02 +7 5677 -7.893005e+01 6.167700e+02 +11 5677 -1.096400e+02 5.053300e+02 +7 5678 -1.307400e+02 6.227100e+02 +9 5678 -8.398500e+02 5.891599e+02 +10 5678 -5.952600e+02 -1.271300e+02 +14 5678 3.711300e+02 3.857800e+02 +16 5678 1.470500e+02 5.518000e+02 +18 5678 -7.917200e+02 2.579299e+02 +7 5679 -1.090800e+02 6.302700e+02 +10 5679 -5.753199e+02 -1.206100e+02 +11 5679 -1.402000e+02 5.160500e+02 +12 5679 -1.235850e+03 -1.878800e+02 +14 5679 3.837500e+02 3.900300e+02 +16 5679 1.639000e+02 5.579100e+02 +7 5680 -3.347200e+02 6.310900e+02 +11 5680 -5.186000e+02 5.414800e+02 +7 5681 5.868300e+02 6.397700e+02 +10 5681 3.016299e+02 -1.185601e+02 +16 5681 5.017300e+02 6.020000e+02 +7 5682 8.409299e+02 5.990991e+01 +9 5682 8.091599e+02 -1.978400e+02 +7 5683 1.325820e+03 1.482100e+02 +9 5683 9.596299e+02 3.199951e+00 +10 5683 6.675300e+02 -5.397700e+02 +12 5683 1.541400e+02 -6.785500e+02 +18 5683 3.180400e+02 -1.300601e+02 +20 5683 2.799500e+02 -3.046500e+02 +7 5684 1.348970e+03 1.622100e+02 +9 5684 9.856599e+02 2.057996e+01 +10 5684 6.852600e+02 -5.277600e+02 +12 5684 1.737900e+02 -6.654800e+02 +18 5684 3.337400e+02 -1.196801e+02 +20 5684 2.930900e+02 -2.956899e+02 +7 5685 1.349700e+03 1.697600e+02 +9 5685 9.862100e+02 2.971997e+01 +10 5685 6.853000e+02 -5.219500e+02 +12 5685 1.741000e+02 -6.589800e+02 +18 5685 3.343300e+02 -1.142400e+02 +20 5685 2.933500e+02 -2.912500e+02 +7 5686 1.341600e+03 1.850601e+02 +9 5686 9.779800e+02 4.733997e+01 +10 5686 6.784099e+02 -5.085200e+02 +12 5686 1.678400e+02 -6.444200e+02 +18 5686 3.292800e+02 -1.030400e+02 +20 5686 2.892800e+02 -2.814700e+02 +7 5687 1.341600e+03 1.850601e+02 +9 5687 9.779800e+02 4.733997e+01 +18 5687 3.292800e+02 -1.030400e+02 +7 5688 1.678000e+02 1.898500e+02 +9 5688 -4.044000e+02 1.984998e+01 +11 5688 2.495100e+02 -3.488000e+01 +12 5688 -9.454600e+02 -6.530100e+02 +7 5689 1.679000e+02 2.114000e+02 +9 5689 -4.045800e+02 4.760999e+01 +12 5689 -9.449600e+02 -6.309200e+02 +7 5690 1.679000e+02 2.114000e+02 +9 5690 -4.045800e+02 4.760999e+01 +11 5690 2.492400e+02 -8.700012e+00 +12 5690 -9.449600e+02 -6.309200e+02 +18 5690 -5.296700e+02 -8.668994e+01 +7 5691 1.004430e+03 2.278101e+02 +9 5691 6.123101e+02 8.453003e+01 +7 5692 1.336200e+02 2.277800e+02 +10 5692 -3.367100e+02 -4.895601e+02 +12 5692 -9.792600e+02 -6.165200e+02 +18 5692 -5.561000e+02 -7.413000e+01 +7 5693 4.474399e+02 2.414900e+02 +10 5693 1.979900e+02 -4.732400e+02 +12 5693 -5.247800e+02 -6.792300e+02 +13 5693 3.097900e+02 2.083600e+02 +16 5693 3.879000e+02 2.715300e+02 +17 5693 -2.025300e+02 2.385000e+02 +18 5693 -9.573999e+01 -1.257600e+02 +20 5693 -6.892004e+01 -3.058300e+02 +7 5694 1.330460e+03 2.433700e+02 +10 5694 6.650100e+02 -4.608199e+02 +20 5694 2.805601e+02 -2.449200e+02 +7 5695 2.444000e+02 2.460200e+02 +10 5695 -2.414700e+02 -4.728700e+02 +7 5696 3.243199e+02 2.518201e+02 +9 5696 -2.431500e+02 1.100200e+02 +10 5696 -1.819700e+02 -4.666899e+02 +11 5696 3.982000e+02 5.078998e+01 +13 5696 -1.508700e+03 1.430500e+02 +7 5697 9.878000e+02 2.594700e+02 +10 5697 4.104900e+02 -4.524301e+02 +12 5697 -1.461000e+02 -5.844301e+02 +17 5697 -7.532000e+02 2.697900e+02 +20 5697 8.643994e+01 -2.400200e+02 +7 5698 1.048930e+03 2.803401e+02 +9 5698 6.642700e+02 1.483800e+02 +17 5698 -6.196000e+02 3.178401e+02 +7 5699 1.205510e+03 2.807600e+02 +10 5699 5.845901e+02 -4.311600e+02 +12 5699 4.931995e+01 -5.632600e+02 +20 5699 2.173600e+02 -2.264000e+02 +7 5700 1.257940e+03 2.874000e+02 +9 5700 9.012300e+02 1.597700e+02 +12 5700 9.430005e+01 -5.569399e+02 +18 5700 2.820900e+02 -3.350000e+01 +7 5701 1.092320e+03 2.902700e+02 +10 5701 4.907300e+02 -4.237100e+02 +12 5701 -5.006995e+01 -5.552900e+02 +7 5702 1.470300e+02 2.938201e+02 +10 5702 -3.247600e+02 -4.282000e+02 +7 5703 1.174410e+03 3.145701e+02 +10 5703 5.565601e+02 -4.027000e+02 +12 5703 2.046997e+01 -5.317900e+02 +7 5704 4.668994e+01 3.231300e+02 +9 5704 -5.577900e+02 1.883000e+02 +16 5704 2.728600e+02 3.296700e+02 +7 5705 4.733600e+02 3.268000e+02 +9 5705 3.585601e+02 9.297998e+01 +13 5705 4.079900e+02 5.654600e+02 +18 5705 -7.905005e+01 -6.757996e+01 +7 5706 4.811899e+02 3.276599e+02 +9 5706 3.678199e+02 9.345996e+01 +7 5707 1.265480e+03 3.371100e+02 +10 5707 6.284199e+02 -3.826400e+02 +12 5707 9.943994e+01 -5.117700e+02 +18 5707 2.858101e+02 2.609985e+00 +7 5708 1.211090e+03 3.507700e+02 +9 5708 8.445601e+02 2.355500e+02 +10 5708 5.847500e+02 -3.714900e+02 +7 5709 1.124050e+03 3.587100e+02 +9 5709 7.439500e+02 2.439500e+02 +10 5709 5.147100e+02 -3.660900e+02 +12 5709 -2.419995e+01 -4.904100e+02 +13 5709 1.661010e+03 5.069600e+02 +17 5709 -4.884301e+02 4.928101e+02 +18 5709 1.875699e+02 2.088000e+01 +20 5709 1.667500e+02 -1.762000e+02 +7 5710 1.134010e+03 3.652400e+02 +9 5710 7.521699e+02 2.510000e+02 +13 5710 1.689340e+03 5.307900e+02 +18 5710 1.931600e+02 2.531995e+01 +7 5711 1.288830e+03 3.687500e+02 +9 5711 9.334399e+02 2.559700e+02 +10 5711 6.449600e+02 -3.556200e+02 +12 5711 1.195300e+02 -4.828500e+02 +18 5711 3.021000e+02 2.539001e+01 +7 5712 1.175300e+03 3.845500e+02 +9 5712 8.015601e+02 2.765300e+02 +10 5712 5.533601e+02 -3.432800e+02 +18 5712 2.221700e+02 3.902002e+01 +20 5712 1.962400e+02 -1.603800e+02 +7 5713 1.088530e+03 3.841500e+02 +10 5713 4.826101e+02 -3.432900e+02 +12 5713 -5.756995e+01 -4.646600e+02 +7 5714 1.108780e+03 3.847700e+02 +9 5714 7.240400e+02 2.761500e+02 +10 5714 4.994299e+02 -3.439900e+02 +13 5714 1.595260e+03 6.089399e+02 +18 5714 1.750601e+02 4.034998e+01 +20 5714 1.561100e+02 -1.596600e+02 +7 5715 -3.155400e+02 4.030601e+02 +9 5715 -1.119140e+03 3.065601e+02 +10 5715 -7.851900e+02 -3.233101e+02 +11 5715 -4.273000e+02 2.365300e+02 +14 5715 2.535000e+02 2.553700e+02 +16 5715 2.073999e+01 3.819700e+02 +20 5715 -8.327100e+02 -1.255500e+02 +7 5716 1.150870e+03 4.034900e+02 +9 5716 7.710400e+02 2.974700e+02 +10 5716 5.311399e+02 -3.292400e+02 +12 5716 -3.280029e+00 -4.500200e+02 +20 5716 1.806200e+02 -1.487200e+02 +7 5717 1.220440e+03 4.048201e+02 +9 5717 8.510701e+02 2.990000e+02 +10 5717 5.869900e+02 -3.275400e+02 +18 5717 2.523400e+02 5.238000e+01 +20 5717 2.223300e+02 -1.482400e+02 +7 5718 -4.902900e+02 4.091500e+02 +11 5718 -7.033700e+02 2.530700e+02 +16 5718 -9.457001e+01 3.822600e+02 +18 5718 -1.150720e+03 1.016100e+02 +7 5719 1.287120e+03 4.288201e+02 +9 5719 9.013201e+02 3.400701e+02 +12 5719 1.117500e+02 -4.182300e+02 +18 5719 2.861100e+02 7.742993e+01 +20 5719 2.497900e+02 -1.270800e+02 +7 5720 -3.318600e+02 4.309800e+02 +9 5720 -1.147350e+03 3.446500e+02 +11 5720 -4.548200e+02 2.729400e+02 +14 5720 2.445400e+02 2.702600e+02 +7 5721 -4.725100e+02 4.435400e+02 +9 5721 -1.380520e+03 3.704800e+02 +11 5721 -6.760900e+02 2.969000e+02 +14 5721 1.637300e+02 2.735600e+02 +18 5721 -1.131380e+03 1.299800e+02 +19 5721 1.180820e+03 3.442100e+02 +7 5722 -4.150100e+02 4.562700e+02 +9 5722 -1.285350e+03 3.896799e+02 +10 5722 -8.879400e+02 -2.708500e+02 +11 5722 -5.860500e+02 3.155300e+02 +14 5722 1.964500e+02 2.867700e+02 +16 5722 -4.695001e+01 4.181899e+02 +19 5722 1.250010e+03 3.719700e+02 +20 5722 -9.213800e+02 -7.885999e+01 +7 5723 -3.805100e+02 4.573401e+02 +9 5723 -1.227070e+03 3.834000e+02 +10 5723 -8.512000e+02 -2.721000e+02 +11 5723 -5.301400e+02 3.084900e+02 +14 5723 2.165700e+02 2.836200e+02 +16 5723 -2.378998e+01 4.198201e+02 +18 5723 -1.034960e+03 1.350701e+02 +19 5723 1.293450e+03 3.786699e+02 +20 5723 -8.893600e+02 -8.294995e+01 +7 5724 -3.319100e+02 4.660801e+02 +9 5724 -1.147970e+03 3.902300e+02 +11 5724 -4.557700e+02 3.155800e+02 +14 5724 2.448300e+02 2.895800e+02 +7 5725 1.012110e+03 4.731599e+02 +9 5725 5.563000e+02 4.034700e+02 +12 5725 -1.381899e+02 -3.657500e+02 +7 5726 -4.670300e+02 4.737800e+02 +9 5726 -1.370950e+03 4.102800e+02 +7 5727 2.800200e+02 4.765400e+02 +10 5727 -2.161000e+02 -2.639700e+02 +13 5727 -1.645350e+03 1.077660e+03 +7 5728 -2.350200e+02 4.769600e+02 +9 5728 -9.907500e+02 4.005901e+02 +11 5728 -3.068800e+02 3.254400e+02 +7 5729 -3.325900e+02 4.800701e+02 +9 5729 -1.147470e+03 4.093401e+02 +10 5729 -8.011300e+02 -2.526600e+02 +11 5729 -4.559200e+02 3.331000e+02 +14 5729 2.453800e+02 2.975900e+02 +16 5729 8.719971e+00 4.386300e+02 +18 5729 -9.857700e+02 1.506799e+02 +20 5729 -8.461500e+02 -7.052002e+01 +7 5730 -3.325900e+02 4.800701e+02 +9 5730 -1.147470e+03 4.093401e+02 +10 5730 -8.011300e+02 -2.526600e+02 +11 5730 -4.559200e+02 3.331000e+02 +14 5730 2.453800e+02 2.975900e+02 +16 5730 8.719971e+00 4.386300e+02 +18 5730 -9.857700e+02 1.506799e+02 +19 5730 1.356030e+03 4.173000e+02 +20 5730 -8.461500e+02 -7.052002e+01 +7 5731 -3.256899e+02 4.829299e+02 +10 5731 -7.938600e+02 -2.492300e+02 +7 5732 -2.844100e+02 4.865000e+02 +9 5732 -1.070340e+03 4.156100e+02 +11 5732 -3.821400e+02 3.415200e+02 +16 5732 4.038000e+01 4.437700e+02 +18 5732 -9.372500e+02 1.541599e+02 +7 5733 -2.923700e+02 4.867200e+02 +9 5733 -1.083620e+03 4.175200e+02 +10 5733 -7.588800e+02 -2.469301e+02 +11 5733 -3.944500e+02 3.415200e+02 +12 5733 -1.457280e+03 -3.235601e+02 +14 5733 2.690300e+02 3.032600e+02 +16 5733 3.510999e+01 4.443000e+02 +18 5733 -9.454600e+02 1.545601e+02 +20 5733 -8.109500e+02 -6.627002e+01 +7 5734 -3.653300e+02 4.874900e+02 +9 5734 -1.201500e+03 4.253000e+02 +11 5734 -5.057800e+02 3.475100e+02 +14 5734 2.262900e+02 3.006400e+02 +7 5735 -2.423800e+02 4.906400e+02 +11 5735 -3.157800e+02 3.420400e+02 +7 5736 -2.774000e+02 4.922900e+02 +9 5736 -1.059400e+03 4.259900e+02 +10 5736 -7.436700e+02 -2.417500e+02 +11 5736 -3.712200e+02 3.488000e+02 +14 5736 2.782000e+02 3.066100e+02 +18 5736 -9.302500e+02 1.577900e+02 +20 5736 -7.977600e+02 -6.348999e+01 +7 5737 1.001060e+03 4.941899e+02 +9 5737 5.412600e+02 4.314900e+02 +12 5737 -1.494900e+02 -3.443600e+02 +17 5737 -1.017270e+03 8.181600e+02 +20 5737 6.466003e+01 -7.627002e+01 +7 5738 -4.181300e+02 4.989399e+02 +9 5738 -1.289270e+03 4.422000e+02 +11 5738 -5.897500e+02 3.650601e+02 +14 5738 1.959000e+02 3.054300e+02 +7 5739 -2.847300e+02 5.038600e+02 +9 5739 -1.070750e+03 4.390200e+02 +11 5739 -3.830400e+02 3.618000e+02 +16 5739 4.033997e+01 4.572500e+02 +7 5740 -5.103003e+01 5.090400e+02 +9 5740 -7.043000e+02 4.305400e+02 +14 5740 4.218800e+02 3.250400e+02 +16 5740 1.989000e+02 4.685100e+02 +7 5741 4.351500e+02 5.106300e+02 +10 5741 1.842300e+02 -2.277300e+02 +12 5741 -5.300700e+02 -4.492900e+02 +17 5741 -2.006000e+02 9.461201e+02 +20 5741 -7.281995e+01 -1.503600e+02 +7 5742 1.074300e+03 5.171799e+02 +10 5742 4.297700e+02 -2.345200e+02 +12 5742 -8.202002e+01 -3.239500e+02 +13 5742 1.286770e+03 1.097770e+03 +7 5743 2.262400e+02 5.209700e+02 +10 5743 -2.576100e+02 -2.241000e+02 +12 5743 -8.790300e+02 -3.190000e+02 +20 5743 -4.111700e+02 -6.052002e+01 +7 5744 1.123190e+03 5.284399e+02 +9 5744 6.883601e+02 4.727000e+02 +12 5744 -3.671997e+01 -3.149700e+02 +7 5745 1.055940e+03 5.293000e+02 +9 5745 6.071201e+02 4.738000e+02 +12 5745 -9.866003e+01 -3.131400e+02 +17 5745 -8.980600e+02 8.899700e+02 +20 5745 9.862000e+01 -5.434998e+01 +7 5746 1.074380e+03 5.296599e+02 +9 5746 6.298201e+02 4.741799e+02 +10 5746 4.291299e+02 -2.243000e+02 +12 5746 -8.175000e+01 -3.130100e+02 +17 5746 -8.568300e+02 8.892500e+02 +20 5746 1.104600e+02 -5.431995e+01 +7 5747 1.074380e+03 5.296599e+02 +9 5747 6.298201e+02 4.741799e+02 +10 5747 4.291299e+02 -2.243000e+02 +12 5747 -8.175000e+01 -3.130100e+02 +17 5747 -8.568300e+02 8.892500e+02 +20 5747 1.104600e+02 -5.431995e+01 +7 5748 1.065190e+03 5.299199e+02 +9 5748 6.185200e+02 4.746699e+02 +10 5748 4.213601e+02 -2.240699e+02 +12 5748 -9.032996e+01 -3.124900e+02 +17 5748 -8.779500e+02 8.903301e+02 +20 5748 1.044100e+02 -5.387000e+01 +7 5749 -2.051100e+02 5.306100e+02 +9 5749 -9.408200e+02 4.696400e+02 +11 5749 -2.591000e+02 3.918000e+02 +14 5749 3.239300e+02 3.319400e+02 +7 5750 -5.396700e+02 5.343101e+02 +9 5750 -1.496080e+03 5.004099e+02 +10 5750 -1.014540e+03 -1.974000e+02 +11 5750 -7.882000e+02 4.200900e+02 +14 5750 1.291700e+02 3.202700e+02 +16 5750 -1.271600e+02 4.718201e+02 +18 5750 -1.201070e+03 2.123201e+02 +19 5750 1.102980e+03 4.474199e+02 +20 5750 -1.033020e+03 -1.609003e+01 +7 5751 -1.911700e+02 5.351699e+02 +9 5751 -9.219400e+02 4.749500e+02 +7 5752 -1.911700e+02 5.351699e+02 +9 5752 -9.219400e+02 4.749500e+02 +7 5753 -5.292600e+02 5.364199e+02 +10 5753 -1.003620e+03 -1.957700e+02 +11 5753 -7.719500e+02 4.217500e+02 +14 5753 1.344900e+02 3.217100e+02 +18 5753 -1.190870e+03 2.132700e+02 +19 5753 1.113650e+03 4.515901e+02 +20 5753 -1.023500e+03 -1.529999e+01 +7 5754 -3.912200e+02 5.444000e+02 +9 5754 -1.250770e+03 5.037000e+02 +10 5754 -8.608700e+02 -1.914900e+02 +11 5754 -5.540500e+02 4.234800e+02 +14 5754 2.122100e+02 3.311400e+02 +16 5754 -2.976001e+01 4.839500e+02 +18 5754 -1.047480e+03 2.116100e+02 +20 5754 -8.993300e+02 -1.791998e+01 +7 5755 1.099080e+03 5.458000e+02 +9 5755 6.591001e+02 4.926100e+02 +10 5755 4.484700e+02 -2.108500e+02 +12 5755 -5.945996e+01 -2.981899e+02 +18 5755 1.420601e+02 1.747700e+02 +7 5756 1.602300e+02 5.531500e+02 +9 5756 -4.215400e+02 4.831000e+02 +11 5756 2.351200e+02 4.095601e+02 +12 5756 -9.411200e+02 -2.875000e+02 +18 5756 -5.338700e+02 1.852800e+02 +20 5756 -4.526200e+02 -3.909998e+01 +7 5757 -3.618800e+02 5.545200e+02 +10 5757 -8.322600e+02 -1.841899e+02 +14 5757 2.290200e+02 3.360700e+02 +7 5758 -4.508600e+02 5.621799e+02 +9 5758 -1.355520e+03 5.313900e+02 +10 5758 -9.228300e+02 -1.738199e+02 +11 5758 -6.539500e+02 4.498700e+02 +7 5759 -2.817100e+02 5.678400e+02 +11 5759 -4.222700e+02 4.540900e+02 +16 5759 5.454004e+01 5.055000e+02 +7 5760 -4.038400e+02 5.684900e+02 +9 5760 -1.275630e+03 5.397400e+02 +10 5760 -8.749200e+02 -1.711500e+02 +11 5760 -5.787600e+02 4.550500e+02 +18 5760 -1.061510e+03 2.342900e+02 +20 5760 -9.113400e+02 1.710022e+00 +7 5761 -5.392700e+02 5.728201e+02 +9 5761 -1.492980e+03 5.523500e+02 +11 5761 -7.861300e+02 4.698101e+02 +16 5761 -1.288400e+02 5.002800e+02 +7 5762 -1.604500e+02 5.783900e+02 +9 5762 -8.796900e+02 5.304600e+02 +10 5762 -6.235100e+02 -1.660800e+02 +11 5762 -2.022200e+02 4.500200e+02 +16 5762 1.248400e+02 5.172300e+02 +20 5762 -6.984000e+02 -7.799988e+00 +7 5763 -6.887000e+01 5.898101e+02 +9 5763 -7.626100e+02 5.447300e+02 +10 5763 -5.407800e+02 -1.583600e+02 +12 5763 -1.196300e+03 -2.310200e+02 +14 5763 4.061300e+02 3.652500e+02 +20 5763 -6.340300e+02 -2.109985e+00 +7 5764 -1.326400e+02 5.993000e+02 +9 5764 -8.403600e+02 5.573000e+02 +10 5764 -5.968000e+02 -1.475500e+02 +11 5764 -1.655500e+02 4.760601e+02 +12 5764 -1.262470e+03 -2.175900e+02 +14 5764 3.693700e+02 3.720000e+02 +16 5764 1.456500e+02 5.341600e+02 +18 5764 -7.925100e+02 2.378500e+02 +20 5764 -6.765900e+02 5.500000e+00 +7 5765 -1.664000e+02 6.074299e+02 +9 5765 -8.925000e+02 5.694800e+02 +10 5765 -6.300300e+02 -1.404100e+02 +11 5765 -2.143700e+02 4.870200e+02 +12 5765 -1.300870e+03 -2.084900e+02 +14 5765 3.487300e+02 3.764500e+02 +16 5765 1.217000e+02 5.388300e+02 +18 5765 -8.239200e+02 2.472200e+02 +20 5765 -7.043900e+02 1.332001e+01 +7 5766 4.944900e+02 6.109399e+02 +10 5766 2.236200e+02 -1.408400e+02 +16 5766 4.251899e+02 5.754299e+02 +18 5766 -6.706006e+01 1.241699e+02 +7 5767 -1.119100e+02 6.116700e+02 +11 5767 -1.432700e+02 4.924100e+02 +7 5768 -1.119100e+02 6.116700e+02 +11 5768 -1.432700e+02 4.924100e+02 +12 5768 -1.240110e+03 -2.071899e+02 +18 5768 -7.773400e+02 2.483401e+02 +7 5769 -3.455100e+02 6.249800e+02 +11 5769 -5.281200e+02 5.338300e+02 +16 5769 1.329004e+01 5.450200e+02 +19 5769 1.362450e+03 5.866100e+02 +7 5770 -3.528300e+02 6.297200e+02 +9 5770 -1.227980e+03 6.274000e+02 +11 5770 -5.378200e+02 5.394500e+02 +7 5771 2.680005e+01 5.490991e+01 +10 5771 -1.410800e+02 -6.541700e+02 +7 5772 1.871200e+02 1.371100e+02 +9 5772 -3.793800e+02 -4.647998e+01 +20 5772 -4.379100e+02 -3.243700e+02 +7 5773 1.357510e+03 1.844199e+02 +9 5773 9.947500e+02 4.694995e+01 +10 5773 6.909099e+02 -5.086000e+02 +12 5773 1.800800e+02 -6.449800e+02 +18 5773 3.396000e+02 -1.035200e+02 +20 5773 2.979700e+02 -2.817500e+02 +7 5774 1.045340e+03 1.988000e+02 +9 5774 6.615000e+02 5.006006e+01 +10 5774 4.607000e+02 -5.033800e+02 +12 5774 -9.218005e+01 -6.410100e+02 +17 5774 -6.241801e+02 1.309700e+02 +18 5774 1.344700e+02 -9.747998e+01 +20 5774 1.228700e+02 -2.786899e+02 +7 5775 1.348880e+03 2.262900e+02 +9 5775 9.836799e+02 9.602002e+01 +10 5775 6.814800e+02 -4.741500e+02 +12 5775 1.719100e+02 -6.060200e+02 +18 5775 3.330300e+02 -7.278003e+01 +20 5775 2.921000e+02 -2.561100e+02 +7 5776 1.211810e+03 2.547900e+02 +9 5776 8.476499e+02 1.214301e+02 +12 5776 5.397998e+01 -5.868500e+02 +18 5776 2.488400e+02 -5.618994e+01 +20 5776 2.202900e+02 -2.422400e+02 +7 5777 1.170250e+03 2.632000e+02 +9 5777 7.999800e+02 1.305400e+02 +7 5778 2.438900e+02 2.626500e+02 +10 5778 -2.414301e+02 -4.570100e+02 +11 5778 3.300800e+02 5.756000e+01 +7 5779 1.330510e+03 2.832200e+02 +10 5779 6.635500e+02 -4.272700e+02 +12 5779 1.542600e+02 -5.538500e+02 +20 5779 2.799500e+02 -2.194399e+02 +7 5780 1.349940e+03 2.899299e+02 +9 5780 9.825901e+02 1.732400e+02 +10 5780 6.786899e+02 -4.205601e+02 +12 5780 1.710300e+02 -5.470000e+02 +7 5781 5.124200e+02 3.000000e+02 +9 5781 4.038101e+02 6.256995e+01 +7 5782 5.286100e+02 3.117400e+02 +9 5782 4.230300e+02 7.497998e+01 +13 5782 6.473101e+02 4.971899e+02 +16 5782 4.526600e+02 3.306500e+02 +7 5783 1.158330e+03 3.134900e+02 +9 5783 7.838201e+02 1.901899e+02 +10 5783 5.435801e+02 -4.038101e+02 +12 5783 5.949951e+00 -5.321200e+02 +20 5783 1.872000e+02 -2.046200e+02 +7 5784 1.440800e+02 3.310601e+02 +9 5784 -4.404800e+02 1.984600e+02 +11 5784 2.181700e+02 1.367800e+02 +12 5784 -9.665500e+02 -5.093300e+02 +7 5785 6.522998e+01 3.306100e+02 +9 5785 -5.377000e+02 1.981000e+02 +11 5785 1.238000e+02 1.353800e+02 +12 5785 -1.047840e+03 -5.087900e+02 +7 5786 1.045760e+03 3.578600e+02 +10 5786 4.548799e+02 -3.673300e+02 +12 5786 -9.413000e+01 -4.924900e+02 +13 5786 1.391100e+03 5.135701e+02 +17 5786 -6.271899e+02 4.964000e+02 +18 5786 1.345400e+02 1.997998e+01 +20 5786 1.217100e+02 -1.775000e+02 +7 5787 1.185240e+03 3.600500e+02 +9 5787 8.149399e+02 2.465300e+02 +12 5787 2.834998e+01 -4.898101e+02 +18 5787 2.292000e+02 2.127002e+01 +7 5788 1.175840e+03 3.597500e+02 +10 5788 5.554099e+02 -3.645000e+02 +12 5788 2.063000e+01 -4.899600e+02 +20 5788 1.979200e+02 -1.759301e+02 +7 5789 1.253740e+03 3.614299e+02 +9 5789 8.931499e+02 2.479299e+02 +10 5789 6.172200e+02 -3.620601e+02 +12 5789 8.746997e+01 -4.890100e+02 +18 5789 2.769399e+02 2.123999e+01 +20 5789 2.430800e+02 -1.754399e+02 +7 5790 1.207510e+03 3.612300e+02 +9 5790 8.398799e+02 2.475200e+02 +10 5790 5.814900e+02 -3.629100e+02 +12 5790 4.919995e+01 -4.889301e+02 +18 5790 2.451801e+02 2.155005e+01 +7 5791 1.278340e+03 3.621100e+02 +9 5791 9.217000e+02 2.486599e+02 +10 5791 6.376201e+02 -3.611600e+02 +12 5791 1.100800e+02 -4.887100e+02 +18 5791 2.957000e+02 2.142004e+01 +20 5791 2.587400e+02 -1.752000e+02 +7 5792 1.265810e+03 3.628500e+02 +9 5792 9.058101e+02 2.496599e+02 +10 5792 6.272400e+02 -3.606600e+02 +12 5792 9.890002e+01 -4.879600e+02 +18 5792 2.857500e+02 2.178003e+01 +20 5792 2.511000e+02 -1.748101e+02 +7 5793 1.183460e+03 3.652600e+02 +9 5793 8.117200e+02 2.525300e+02 +10 5793 5.611299e+02 -3.596400e+02 +12 5793 2.681995e+01 -4.846899e+02 +18 5793 2.278199e+02 2.485999e+01 +20 5793 2.014100e+02 -1.724700e+02 +7 5794 1.148630e+03 3.647900e+02 +9 5794 7.718000e+02 2.516500e+02 +10 5794 5.331201e+02 -3.605200e+02 +12 5794 -3.630005e+00 -4.848300e+02 +20 5794 1.815800e+02 -1.725400e+02 +7 5795 1.140970e+03 3.649500e+02 +10 5795 5.262700e+02 -3.601400e+02 +7 5796 1.279360e+03 3.673700e+02 +10 5796 6.388301e+02 -3.566300e+02 +12 5796 1.112500e+02 -4.839399e+02 +18 5796 2.958199e+02 2.508997e+01 +7 5797 3.125800e+02 3.761699e+02 +9 5797 -2.555400e+02 2.664800e+02 +11 5797 3.885699e+02 2.023500e+02 +12 5797 -8.050600e+02 -4.597400e+02 +18 5797 -4.303000e+02 4.881006e+01 +7 5798 1.408800e+02 3.770400e+02 +10 5798 -3.308500e+02 -3.528600e+02 +7 5799 1.020660e+03 3.807100e+02 +9 5799 6.268101e+02 2.694500e+02 +10 5799 4.320400e+02 -3.481300e+02 +12 5799 -1.173700e+02 -4.704700e+02 +13 5799 1.292100e+03 6.042000e+02 +17 5799 -6.905800e+02 5.516500e+02 +18 5799 1.154100e+02 3.768005e+01 +20 5799 1.051500e+02 -1.617800e+02 +7 5800 1.155750e+03 3.927400e+02 +9 5800 7.781799e+02 2.855701e+02 +10 5800 5.375100e+02 -3.368600e+02 +12 5800 2.130005e+00 -4.591300e+02 +7 5801 1.155750e+03 3.927400e+02 +9 5801 7.781799e+02 2.855701e+02 +10 5801 5.375100e+02 -3.368600e+02 +12 5801 2.130005e+00 -4.591300e+02 +7 5802 -3.989100e+02 3.947600e+02 +9 5802 -1.254060e+03 2.992100e+02 +10 5802 -8.710700e+02 -3.300300e+02 +11 5802 -5.546800e+02 2.294900e+02 +14 5802 2.045400e+02 2.487900e+02 +16 5802 -3.490997e+01 3.736200e+02 +20 5802 -9.060900e+02 -1.279700e+02 +7 5803 -3.618700e+02 3.974800e+02 +9 5803 -1.193610e+03 3.010901e+02 +11 5803 -4.973700e+02 2.315500e+02 +14 5803 2.263700e+02 2.511100e+02 +18 5803 -1.015480e+03 8.364001e+01 +19 5803 1.317000e+03 3.023201e+02 +20 5803 -8.727100e+02 -1.275601e+02 +7 5804 -4.023800e+02 4.002600e+02 +9 5804 -1.262840e+03 3.044700e+02 +11 5804 -5.640000e+02 2.355800e+02 +14 5804 2.023200e+02 2.506200e+02 +19 5804 1.266590e+03 3.003201e+02 +7 5805 -5.375800e+02 4.007100e+02 +9 5805 -1.491280e+03 3.142600e+02 +10 5805 -1.018610e+03 -3.223900e+02 +11 5805 -7.812500e+02 2.442600e+02 +14 5805 1.273800e+02 2.483700e+02 +16 5805 -1.251500e+02 3.741300e+02 +18 5805 -1.201560e+03 9.695996e+01 +19 5805 1.105550e+03 2.795200e+02 +20 5805 -1.035140e+03 -1.167200e+02 +7 5806 -5.265000e+02 4.017800e+02 +9 5806 -1.472080e+03 3.148900e+02 +10 5806 -1.006480e+03 -3.221500e+02 +11 5806 -7.632100e+02 2.448700e+02 +18 5806 -1.189840e+03 9.673999e+01 +19 5806 1.117830e+03 2.828301e+02 +20 5806 -1.024760e+03 -1.166500e+02 +7 5807 -5.339400e+02 4.048800e+02 +9 5807 -1.485320e+03 3.205000e+02 +14 5807 1.290400e+02 2.508500e+02 +16 5807 -1.225500e+02 3.778700e+02 +19 5807 1.109680e+03 2.855500e+02 +20 5807 -1.031720e+03 -1.138500e+02 +7 5808 -2.676400e+02 4.086300e+02 +9 5808 -1.037910e+03 3.109700e+02 +11 5808 -3.503900e+02 2.407700e+02 +16 5808 5.287000e+01 3.875200e+02 +7 5809 1.177830e+03 4.096899e+02 +9 5809 8.015300e+02 3.068101e+02 +18 5809 2.229700e+02 5.794995e+01 +7 5810 3.080800e+02 4.130400e+02 +9 5810 -2.608101e+02 3.141599e+02 +10 5810 -1.945300e+02 -3.216100e+02 +12 5810 -8.068200e+02 -4.223000e+02 +13 5810 -1.555190e+03 8.066300e+02 +18 5810 -4.335900e+02 7.790002e+01 +20 5810 -3.668600e+02 -1.310400e+02 +7 5811 -2.658500e+02 4.169399e+02 +9 5811 -1.037870e+03 3.225901e+02 +10 5811 -7.328300e+02 -3.115100e+02 +11 5811 -3.506200e+02 2.517000e+02 +12 5811 -1.427810e+03 -3.999100e+02 +14 5811 2.837100e+02 2.643000e+02 +16 5811 5.300000e+01 3.932600e+02 +18 5811 -9.190500e+02 9.439001e+01 +20 5811 -7.881800e+02 -1.182400e+02 +7 5812 -5.549600e+02 4.271899e+02 +9 5812 -1.519640e+03 3.534199e+02 +19 5812 1.085690e+03 3.105500e+02 +7 5813 1.159010e+03 4.412300e+02 +10 5813 5.347500e+02 -2.965300e+02 +12 5813 3.709961e+00 -4.131700e+02 +20 5813 1.837100e+02 -1.234900e+02 +7 5814 1.153770e+03 4.437700e+02 +9 5814 7.700400e+02 3.487500e+02 +10 5814 5.298601e+02 -2.945200e+02 +12 5814 -1.329956e+00 -4.104301e+02 +18 5814 2.046899e+02 8.446997e+01 +20 5814 1.806200e+02 -1.217200e+02 +7 5815 -4.433000e+02 4.448101e+02 +11 5815 -6.276800e+02 2.947000e+02 +7 5816 -4.020400e+02 4.507200e+02 +9 5816 -1.260990e+03 3.740601e+02 +11 5816 -5.626600e+02 2.998500e+02 +14 5816 2.039800e+02 2.794400e+02 +16 5816 -3.794000e+01 4.138101e+02 +19 5816 1.266360e+03 3.649800e+02 +20 5816 -9.084300e+02 -8.712000e+01 +7 5817 -5.361200e+02 4.558101e+02 +9 5817 -1.486420e+03 3.901100e+02 +10 5817 -1.014050e+03 -2.713300e+02 +11 5817 -7.781900e+02 3.161100e+02 +14 5817 1.293900e+02 2.783000e+02 +16 5817 -1.250800e+02 4.147700e+02 +19 5817 1.106070e+03 3.497400e+02 +20 5817 -1.031050e+03 -7.594995e+01 +7 5818 -5.018200e+02 4.611100e+02 +9 5818 -1.428670e+03 3.955901e+02 +10 5818 -9.773400e+02 -2.669700e+02 +11 5818 -7.222900e+02 3.198800e+02 +16 5818 -1.029900e+02 4.197400e+02 +20 5818 -9.990700e+02 -7.400000e+01 +7 5819 -4.845700e+02 4.684099e+02 +9 5819 -1.399800e+03 4.054500e+02 +11 5819 -6.940100e+02 3.299900e+02 +7 5820 -3.261400e+02 4.738000e+02 +9 5820 -1.137930e+03 4.039700e+02 +10 5820 -7.944900e+02 -2.583600e+02 +11 5820 -4.456400e+02 3.286300e+02 +16 5820 1.262000e+01 4.345200e+02 +18 5820 -9.793900e+02 1.470200e+02 +19 5820 1.363730e+03 4.119800e+02 +7 5821 -2.921000e+02 4.747200e+02 +11 5821 -3.940100e+02 3.260600e+02 +14 5821 2.688700e+02 2.962700e+02 +16 5821 3.560999e+01 4.363600e+02 +19 5821 1.409070e+03 4.178500e+02 +7 5822 1.027960e+03 4.762100e+02 +9 5822 5.780400e+02 4.055100e+02 +12 5822 -1.234399e+02 -3.624500e+02 +20 5822 8.209998e+01 -8.815002e+01 +7 5823 4.649301e+02 4.772600e+02 +9 5823 3.524500e+02 2.529800e+02 +7 5824 1.763199e+02 4.780801e+02 +10 5824 -2.984200e+02 -2.621100e+02 +12 5824 -9.285100e+02 -3.615400e+02 +7 5825 -2.778600e+02 4.783201e+02 +10 5825 -7.439300e+02 -2.552300e+02 +7 5826 -2.778600e+02 4.783201e+02 +10 5826 -7.439300e+02 -2.552300e+02 +11 5826 -3.715800e+02 3.299400e+02 +12 5826 -1.439640e+03 -3.338101e+02 +18 5826 -9.309300e+02 1.466000e+02 +20 5826 -7.981400e+02 -7.340002e+01 +7 5827 -2.970800e+02 4.798800e+02 +9 5827 -1.089250e+03 4.094399e+02 +10 5827 -7.647200e+02 -2.533500e+02 +11 5827 -4.001000e+02 3.333600e+02 +18 5827 -9.495700e+02 1.495200e+02 +19 5827 1.400840e+03 4.238101e+02 +20 5827 -8.141200e+02 -7.082996e+01 +7 5828 1.012690e+03 4.887500e+02 +9 5828 5.577800e+02 4.242500e+02 +12 5828 -1.377100e+02 -3.498199e+02 +18 5828 7.918994e+01 1.341000e+02 +7 5829 1.014910e+03 4.947700e+02 +9 5829 5.610200e+02 4.315901e+02 +12 5829 -1.350500e+02 -3.447100e+02 +18 5829 8.146997e+01 1.378800e+02 +20 5829 7.448999e+01 -7.657996e+01 +7 5830 -3.516000e+02 5.019299e+02 +10 5830 -8.194200e+02 -2.317200e+02 +7 5831 -4.397300e+02 5.030000e+02 +10 5831 -9.141400e+02 -2.285800e+02 +7 5832 1.103490e+03 5.094600e+02 +9 5832 6.649800e+02 4.484500e+02 +10 5832 4.535701e+02 -2.409500e+02 +12 5832 -5.503003e+01 -3.325200e+02 +17 5832 -7.914600e+02 8.373600e+02 +20 5832 1.288199e+02 -6.789001e+01 +7 5833 1.055810e+03 5.094299e+02 +9 5833 6.070601e+02 4.492100e+02 +12 5833 -9.869995e+01 -3.308900e+02 +20 5833 9.872998e+01 -6.703003e+01 +7 5834 1.859200e+02 5.094299e+02 +11 5834 2.656100e+02 3.565800e+02 +7 5835 -2.545500e+02 5.090400e+02 +9 5835 -1.021640e+03 4.445601e+02 +11 5835 -3.357900e+02 3.675100e+02 +14 5835 2.926000e+02 3.169800e+02 +7 5836 1.074180e+03 5.103301e+02 +9 5836 6.300601e+02 4.501699e+02 +10 5836 4.298899e+02 -2.396700e+02 +12 5836 -8.207996e+01 -3.309399e+02 +13 5836 1.286560e+03 1.071200e+03 +17 5836 -8.562000e+02 8.446500e+02 +20 5836 1.104900e+02 -6.656995e+01 +7 5837 -4.019100e+02 5.099500e+02 +9 5837 -1.264860e+03 4.527700e+02 +10 5837 -8.717300e+02 -2.237100e+02 +11 5837 -5.648300e+02 3.766200e+02 +14 5837 2.050000e+02 3.120500e+02 +16 5837 -3.790002e+01 4.587600e+02 +19 5837 1.265910e+03 4.431599e+02 +7 5838 -5.733997e+01 5.123401e+02 +9 5838 -7.137800e+02 4.358600e+02 +14 5838 4.177500e+02 3.266900e+02 +16 5838 1.949700e+02 4.708201e+02 +7 5839 1.971000e+02 5.173700e+02 +10 5839 -2.811899e+02 -2.268800e+02 +7 5840 1.065040e+03 5.180400e+02 +9 5840 6.184099e+02 4.600100e+02 +10 5840 4.218999e+02 -2.334800e+02 +20 5840 1.045300e+02 -6.195996e+01 +7 5841 1.055490e+03 5.175000e+02 +9 5841 6.071299e+02 4.589800e+02 +12 5841 -9.880005e+01 -3.238600e+02 +17 5841 -8.981700e+02 8.632400e+02 +20 5841 9.851001e+01 -6.193005e+01 +7 5842 -1.888000e+01 5.229500e+02 +10 5842 -4.800100e+02 -2.189700e+02 +7 5843 -2.551300e+02 5.295000e+02 +10 5843 -7.192700e+02 -2.083500e+02 +12 5843 -1.407730e+03 -2.821000e+02 +14 5843 2.925800e+02 3.289000e+02 +16 5843 5.920996e+01 4.775400e+02 +18 5843 -9.070100e+02 1.875400e+02 +7 5844 -3.442400e+02 5.301300e+02 +10 5844 -8.162900e+02 -2.063000e+02 +14 5844 2.382400e+02 3.230300e+02 +16 5844 6.650024e+00 4.761700e+02 +19 5844 1.353190e+03 4.785801e+02 +7 5845 8.398999e+01 5.344500e+02 +10 5845 -3.822100e+02 -2.100500e+02 +16 5845 2.989600e+02 4.917000e+02 +7 5846 -5.137800e+02 5.383800e+02 +9 5846 -1.451840e+03 5.034700e+02 +18 5846 -1.173730e+03 2.138101e+02 +20 5846 -1.008180e+03 -1.541998e+01 +7 5847 -4.852800e+02 5.385300e+02 +10 5847 -9.568200e+02 -1.950699e+02 +16 5847 -9.356000e+01 4.767600e+02 +19 5847 1.165370e+03 4.639000e+02 +7 5848 1.103650e+03 5.399399e+02 +9 5848 6.645601e+02 4.872400e+02 +10 5848 4.524299e+02 -2.151000e+02 +12 5848 -5.539001e+01 -3.037200e+02 +17 5848 -7.928200e+02 9.092200e+02 +18 5848 1.452600e+02 1.702700e+02 +20 5848 1.286200e+02 -4.951001e+01 +7 5849 -7.696900e+02 5.417900e+02 +11 5849 -9.508800e+02 4.039800e+02 +7 5850 1.109820e+03 5.424700e+02 +9 5850 6.698999e+02 4.895601e+02 +10 5850 4.565701e+02 -2.134100e+02 +12 5850 -5.089001e+01 -3.021000e+02 +17 5850 -7.811500e+02 9.123000e+02 +18 5850 1.492800e+02 1.716100e+02 +20 5850 1.319900e+02 -4.756006e+01 +7 5851 -5.255200e+02 5.447600e+02 +9 5851 -1.469940e+03 5.128900e+02 +10 5851 -9.986600e+02 -1.884700e+02 +11 5851 -7.640400e+02 4.323800e+02 +14 5851 1.369800e+02 3.265300e+02 +16 5851 -1.190700e+02 4.803201e+02 +19 5851 1.118580e+03 4.633101e+02 +7 5852 1.133000e+02 5.458401e+02 +10 5852 -3.563101e+02 -2.003300e+02 +7 5853 -2.033500e+02 5.465901e+02 +9 5853 -9.389900e+02 4.901500e+02 +11 5853 -2.576200e+02 4.111500e+02 +7 5854 -1.895699e+02 5.483800e+02 +11 5854 -2.382400e+02 4.124800e+02 +7 5855 -1.835400e+02 5.497400e+02 +11 5855 -2.281000e+02 4.143800e+02 +14 5855 3.374900e+02 3.440000e+02 +7 5856 -3.149200e+02 5.512900e+02 +10 5856 -7.888200e+02 -1.872500e+02 +11 5856 -4.546300e+02 4.323700e+02 +7 5857 -3.313800e+02 5.519800e+02 +10 5857 -8.052100e+02 -1.863000e+02 +11 5857 -4.782100e+02 4.325400e+02 +16 5857 1.483997e+01 4.916799e+02 +18 5857 -9.956000e+02 2.158101e+02 +19 5857 1.368080e+03 5.056500e+02 +7 5858 -2.644600e+02 5.563600e+02 +11 5858 -3.971400e+02 4.367100e+02 +7 5859 -2.572500e+02 5.574299e+02 +9 5859 -1.072100e+03 5.183500e+02 +11 5859 -3.884800e+02 4.355900e+02 +18 5859 -9.342000e+02 2.161400e+02 +20 5859 -8.006800e+02 -1.278998e+01 +7 5860 -3.901801e+02 5.695601e+02 +10 5860 -8.597500e+02 -1.690500e+02 +11 5860 -5.577700e+02 4.575100e+02 +16 5860 -2.910999e+01 5.034800e+02 +19 5860 1.285670e+03 5.209299e+02 +7 5861 -1.023700e+02 5.730100e+02 +9 5861 -7.989800e+02 5.244000e+02 +10 5861 -5.686500e+02 -1.718400e+02 +14 5861 3.871200e+02 3.572200e+02 +7 5862 -4.472600e+02 5.761200e+02 +11 5862 -6.492100e+02 4.693600e+02 +14 5862 1.805500e+02 3.448800e+02 +7 5863 -8.431006e+01 5.771200e+02 +9 5863 -7.787100e+02 5.280300e+02 +10 5863 -5.531300e+02 -1.689900e+02 +12 5863 -1.212370e+03 -2.442900e+02 +16 5863 1.810601e+02 5.178700e+02 +18 5863 -7.533900e+02 2.176899e+02 +20 5863 -6.431700e+02 -1.146997e+01 +7 5864 5.645601e+02 5.812500e+02 +10 5864 2.912500e+02 -1.673600e+02 +7 5865 -6.983997e+01 5.826100e+02 +9 5865 -7.611700e+02 5.318600e+02 +10 5865 -5.409600e+02 -1.650900e+02 +14 5865 4.056800e+02 3.617400e+02 +16 5865 1.960200e+02 5.232600e+02 +7 5866 -3.641200e+02 5.856200e+02 +11 5866 -5.185800e+02 4.749800e+02 +7 5867 -5.006600e+02 5.880500e+02 +10 5867 -9.705600e+02 -1.495699e+02 +16 5867 -1.028000e+02 5.130900e+02 +19 5867 1.147000e+03 5.228600e+02 +7 5868 -2.950000e+01 5.954000e+02 +9 5868 -7.174100e+02 5.505400e+02 +18 5868 -7.145400e+02 2.316100e+02 +20 5868 -6.094100e+02 2.600098e-01 +7 5869 -7.647998e+01 5.981799e+02 +9 5869 -7.719800e+02 5.556699e+02 +10 5869 -5.472800e+02 -1.506500e+02 +11 5869 -1.023200e+02 4.743500e+02 +12 5869 -1.204150e+03 -2.209700e+02 +14 5869 4.019300e+02 3.704500e+02 +16 5869 1.901000e+02 5.354600e+02 +18 5869 -7.490800e+02 2.359099e+02 +20 5869 -6.390000e+02 3.679993e+00 +7 5870 -1.229301e+02 6.071500e+02 +10 5870 -5.870800e+02 -1.411700e+02 +12 5870 -1.251230e+03 -2.116700e+02 +16 5870 1.542000e+02 5.395500e+02 +7 5871 -1.763000e+01 6.106000e+02 +9 5871 -6.953100e+02 5.708101e+02 +11 5871 -3.120001e+01 4.900701e+02 +14 5871 4.381600e+02 3.754800e+02 +7 5872 4.984900e+02 6.183300e+02 +9 5872 3.773300e+02 4.079900e+02 +10 5872 2.280500e+02 -1.342800e+02 +18 5872 -6.331006e+01 1.290500e+02 +7 5873 -3.044800e+02 6.194600e+02 +9 5873 -1.166820e+03 6.145000e+02 +11 5873 -4.811400e+02 5.276600e+02 +12 5873 -1.490010e+03 -1.672900e+02 +14 5873 2.600700e+02 3.655400e+02 +18 5873 -9.896500e+02 2.780200e+02 +7 5874 -4.658900e+02 6.342900e+02 +10 5874 -9.365300e+02 -1.080601e+02 +11 5874 -6.822900e+02 5.475100e+02 +19 5874 1.193040e+03 5.845400e+02 +20 5874 -9.663700e+02 5.398999e+01 +7 5875 -4.045900e+02 6.368300e+02 +9 5875 -1.295340e+03 6.362700e+02 +20 5875 -9.192000e+02 5.369995e+01 +7 5876 6.892004e+01 9.776001e+01 +10 5876 -1.067500e+02 -6.114301e+02 +11 5876 7.314500e+02 -2.239400e+02 +7 5877 6.892004e+01 9.776001e+01 +10 5877 -1.067500e+02 -6.114301e+02 +11 5877 7.314500e+02 -2.239400e+02 +7 5878 1.355930e+03 1.433401e+02 +9 5878 9.943899e+02 -2.229980e+00 +12 5878 1.798600e+02 -6.830000e+02 +7 5879 1.266350e+03 1.464900e+02 +9 5879 9.140701e+02 -7.030029e+00 +18 5879 2.885300e+02 -1.357300e+02 +7 5880 1.355590e+03 1.500701e+02 +9 5880 9.935500e+02 5.880005e+00 +12 5880 1.796100e+02 -6.769000e+02 +18 5880 3.383800e+02 -1.289100e+02 +20 5880 2.976300e+02 -3.035300e+02 +7 5881 1.105690e+03 1.540901e+02 +10 5881 5.211899e+02 -5.400601e+02 +12 5881 -3.479004e+01 -6.826600e+02 +20 5881 1.659200e+02 -3.071200e+02 +7 5882 1.074710e+03 1.579700e+02 +9 5882 6.977700e+02 1.910034e+00 +7 5883 1.343890e+03 1.586599e+02 +9 5883 9.817600e+02 1.578003e+01 +12 5883 1.699500e+02 -6.687800e+02 +7 5884 1.739900e+02 1.594099e+02 +11 5884 2.573600e+02 -7.163000e+01 +18 5884 -5.251200e+02 -1.271700e+02 +7 5885 1.739500e+02 1.639700e+02 +9 5885 -3.959399e+02 -1.335999e+01 +11 5885 2.572600e+02 -6.662000e+01 +7 5886 1.356530e+03 1.934900e+02 +10 5886 6.895601e+02 -5.009800e+02 +12 5886 1.791100e+02 -6.369200e+02 +18 5886 3.395300e+02 -9.631995e+01 +20 5886 2.974301e+02 -2.759100e+02 +7 5887 4.393700e+02 2.122300e+02 +10 5887 1.911801e+02 -4.989399e+02 +18 5887 -1.006200e+02 -1.453600e+02 +7 5888 1.244900e+03 2.491500e+02 +10 5888 6.143799e+02 -4.577600e+02 +12 5888 8.190002e+01 -5.931700e+02 +18 5888 2.710500e+02 -6.107996e+01 +20 5888 2.389100e+02 -2.461700e+02 +7 5889 4.470500e+02 2.519600e+02 +9 5889 3.341000e+02 1.102002e+01 +7 5890 5.121100e+02 2.527800e+02 +9 5890 4.052400e+02 1.206995e+01 +13 5890 5.791399e+02 2.564000e+02 +16 5890 4.384000e+02 2.818700e+02 +7 5891 5.121100e+02 2.527800e+02 +9 5891 4.052400e+02 1.206995e+01 +13 5891 5.791399e+02 2.564000e+02 +16 5891 4.384000e+02 2.818700e+02 +7 5892 1.349770e+03 2.546100e+02 +9 5892 9.835601e+02 1.312200e+02 +10 5892 6.811001e+02 -4.525100e+02 +20 5892 2.918300e+02 -2.378900e+02 +7 5893 2.949301e+02 2.592300e+02 +10 5893 -2.026899e+02 -4.597700e+02 +7 5894 1.349590e+03 2.605100e+02 +10 5894 6.800801e+02 -4.452900e+02 +12 5894 1.714100e+02 -5.747100e+02 +18 5894 3.332400e+02 -4.789001e+01 +20 5894 2.918300e+02 -2.339900e+02 +7 5895 3.291801e+02 2.629900e+02 +9 5895 -2.370400e+02 1.244000e+02 +7 5896 4.852100e+02 2.654500e+02 +9 5896 3.757400e+02 2.534998e+01 +13 5896 4.667800e+02 3.081899e+02 +7 5897 4.785800e+02 2.708201e+02 +9 5897 3.669100e+02 3.197998e+01 +7 5898 1.878800e+02 2.875901e+02 +10 5898 -2.896300e+02 -4.330100e+02 +7 5899 1.331590e+03 3.047200e+02 +10 5899 6.628701e+02 -4.087200e+02 +7 5900 4.617000e+02 3.382400e+02 +9 5900 3.456500e+02 1.047700e+02 +13 5900 3.584600e+02 6.096000e+02 +7 5901 -7.971000e+02 3.416799e+02 +11 5901 -9.066600e+02 1.336200e+02 +14 5901 -2.603000e+01 2.417200e+02 +16 5901 -3.724900e+02 3.247000e+02 +7 5902 1.659399e+02 3.444700e+02 +11 5902 2.445500e+02 1.543800e+02 +12 5902 -9.429300e+02 -4.953700e+02 +18 5902 -5.306400e+02 2.008997e+01 +20 5902 -4.506700e+02 -1.810699e+02 +7 5903 1.404800e+02 3.453700e+02 +9 5903 -4.415200e+02 2.172400e+02 +10 5903 -3.313300e+02 -3.813000e+02 +12 5903 -9.687700e+02 -4.945000e+02 +16 5903 3.449000e+02 3.488900e+02 +20 5903 -4.677700e+02 -1.804600e+02 +7 5904 1.272710e+03 3.627900e+02 +9 5904 9.153601e+02 2.494500e+02 +7 5905 -4.861500e+02 3.729600e+02 +9 5905 -1.404660e+03 2.774000e+02 +11 5905 -6.976500e+02 2.088600e+02 +7 5906 1.072960e+03 3.742900e+02 +9 5906 6.901799e+02 2.610500e+02 +7 5907 2.741300e+02 3.865000e+02 +10 5907 -2.195699e+02 -3.448300e+02 +13 5907 -1.671260e+03 7.072900e+02 +7 5908 1.188070e+03 3.881000e+02 +9 5908 8.165901e+02 2.803301e+02 +10 5908 5.640801e+02 -3.406801e+02 +12 5908 3.089001e+01 -4.641200e+02 +18 5908 2.318400e+02 4.122998e+01 +20 5908 2.045200e+02 -1.584500e+02 +7 5909 1.207300e+03 3.919800e+02 +10 5909 5.785300e+02 -3.368101e+02 +12 5909 4.685999e+01 -4.606000e+02 +20 5909 2.151400e+02 -1.554500e+02 +7 5910 -3.242100e+02 3.998000e+02 +9 5910 -1.134300e+03 3.027100e+02 +10 5910 -7.947400e+02 -3.260100e+02 +11 5910 -4.422800e+02 2.330900e+02 +18 5910 -9.791800e+02 8.371997e+01 +19 5910 1.367500e+03 3.115400e+02 +20 5910 -8.407900e+02 -1.272600e+02 +7 5911 1.224410e+03 4.004399e+02 +9 5911 8.566201e+02 2.948600e+02 +18 5911 2.562400e+02 5.031006e+01 +7 5912 -3.123400e+02 4.034600e+02 +9 5912 -1.113890e+03 3.062400e+02 +11 5912 -4.223800e+02 2.363000e+02 +20 5912 -8.299400e+02 -1.257900e+02 +7 5913 1.476300e+02 4.081000e+02 +9 5913 -4.301200e+02 2.980100e+02 +7 5914 2.116100e+02 4.110701e+02 +11 5914 2.951600e+02 2.369300e+02 +7 5915 3.462300e+02 4.180300e+02 +10 5915 -1.674600e+02 -3.166400e+02 +7 5916 1.292600e+03 4.221100e+02 +10 5916 6.234399e+02 -3.121000e+02 +12 5916 1.174301e+02 -4.246600e+02 +7 5917 1.292600e+03 4.221100e+02 +9 5917 9.088301e+02 3.326000e+02 +10 5917 6.234399e+02 -3.121000e+02 +12 5917 1.174301e+02 -4.246600e+02 +18 5917 2.904399e+02 7.226001e+01 +7 5918 9.884299e+02 4.250701e+02 +9 5918 5.884800e+02 3.218800e+02 +12 5918 -1.475100e+02 -4.284600e+02 +7 5919 9.735500e+02 4.248201e+02 +10 5919 3.916899e+02 -3.109700e+02 +12 5919 -1.601801e+02 -4.284500e+02 +7 5920 1.019940e+03 4.256200e+02 +10 5920 4.295801e+02 -3.101400e+02 +12 5920 -1.185699e+02 -4.284301e+02 +13 5920 1.289210e+03 7.759100e+02 +7 5921 1.010680e+03 4.255601e+02 +9 5921 6.143601e+02 3.227400e+02 +10 5921 4.221499e+02 -3.102400e+02 +12 5921 -1.269700e+02 -4.283700e+02 +13 5921 1.256160e+03 7.765100e+02 +20 5921 9.893994e+01 -1.339600e+02 +7 5922 1.045810e+03 4.269199e+02 +9 5922 6.561499e+02 3.238401e+02 +10 5922 4.514199e+02 -3.088700e+02 +12 5922 -9.526001e+01 -4.280500e+02 +13 5922 1.386230e+03 7.779000e+02 +17 5922 -6.329399e+02 6.556600e+02 +18 5922 1.341500e+02 7.109009e+01 +20 5922 1.213300e+02 -1.335699e+02 +7 5923 1.036220e+03 4.269099e+02 +10 5923 4.437600e+02 -3.087300e+02 +12 5923 -1.033900e+02 -4.275601e+02 +13 5923 1.351630e+03 7.796400e+02 +18 5923 1.274500e+02 7.140002e+01 +7 5924 1.154170e+03 4.380000e+02 +9 5924 7.715400e+02 3.408700e+02 +10 5924 5.309700e+02 -2.990200e+02 +12 5924 -4.799805e-01 -4.161700e+02 +18 5924 2.052100e+02 8.009998e+01 +7 5925 1.176950e+03 4.386000e+02 +10 5925 5.490100e+02 -2.983800e+02 +12 5925 1.930005e+01 -4.159700e+02 +18 5925 2.210500e+02 7.990002e+01 +20 5925 1.948500e+02 -1.251500e+02 +7 5926 1.176170e+03 4.447200e+02 +9 5926 7.960200e+02 3.493700e+02 +12 5926 1.831995e+01 -4.101801e+02 +18 5926 2.201899e+02 8.448999e+01 +7 5927 1.176170e+03 4.447200e+02 +9 5927 7.960000e+02 3.492000e+02 +10 5927 5.478401e+02 -2.939200e+02 +12 5927 1.831995e+01 -4.101801e+02 +18 5927 2.201899e+02 8.448999e+01 +20 5927 1.943101e+02 -1.220601e+02 +7 5928 -4.538800e+02 4.451500e+02 +9 5928 -1.346790e+03 3.727500e+02 +20 5928 -9.547700e+02 -8.700000e+01 +7 5929 -3.991600e+02 4.559500e+02 +9 5929 -1.256550e+03 3.832000e+02 +11 5929 -5.577700e+02 3.084900e+02 +18 5929 -1.053980e+03 1.354500e+02 +7 5930 -3.292700e+02 4.596300e+02 +9 5930 -1.140620e+03 3.835701e+02 +10 5930 -7.970400e+02 -2.709399e+02 +11 5930 -4.482900e+02 3.093500e+02 +18 5930 -9.818700e+02 1.342600e+02 +19 5930 1.359970e+03 3.911400e+02 +20 5930 -8.426500e+02 -8.382996e+01 +7 5931 -5.385400e+02 4.856000e+02 +9 5931 -1.493600e+03 4.327300e+02 +10 5931 -1.015380e+03 -2.425800e+02 +20 5931 -1.033740e+03 -5.262000e+01 +7 5932 -5.295700e+02 4.870601e+02 +9 5932 -1.478190e+03 4.341500e+02 +7 5933 3.234200e+02 4.947200e+02 +10 5933 -1.984500e+02 -2.494200e+02 +12 5933 -8.019300e+02 -3.320500e+02 +7 5934 1.102940e+03 4.977100e+02 +9 5934 6.648000e+02 4.339500e+02 +12 5934 -5.548999e+01 -3.433300e+02 +17 5934 -7.919600e+02 8.114600e+02 +18 5934 1.449700e+02 1.386899e+02 +20 5934 1.285000e+02 -7.514001e+01 +7 5935 2.019700e+02 5.075000e+02 +9 5935 -3.702500e+02 4.255300e+02 +7 5936 1.050510e+03 5.081500e+02 +9 5936 6.016101e+02 4.468000e+02 +12 5936 -1.029200e+02 -3.330200e+02 +13 5936 1.197220e+03 1.065790e+03 +20 5936 9.515002e+01 -6.754004e+01 +7 5937 1.187610e+03 5.097400e+02 +9 5937 7.645200e+02 4.484099e+02 +13 5937 1.699350e+03 1.054550e+03 +17 5937 -6.119700e+02 8.273700e+02 +18 5937 2.058600e+02 1.457300e+02 +7 5938 1.177210e+03 5.096599e+02 +9 5938 7.523101e+02 4.482700e+02 +10 5938 5.126299e+02 -2.406899e+02 +12 5938 1.096997e+01 -3.344301e+02 +13 5938 1.661580e+03 1.054250e+03 +17 5938 -6.338800e+02 8.284600e+02 +7 5939 -5.401800e+02 5.132500e+02 +9 5939 -1.495990e+03 4.697200e+02 +20 5939 -1.033920e+03 -3.268005e+01 +7 5940 -2.607900e+02 5.171200e+02 +9 5940 -1.031380e+03 4.557900e+02 +11 5940 -3.445600e+02 3.780800e+02 +14 5940 2.891400e+02 3.216500e+02 +18 5940 -9.123500e+02 1.775701e+02 +20 5940 -7.814800e+02 -4.640002e+01 +7 5941 -1.999500e+02 5.254900e+02 +11 5941 -2.531700e+02 3.847200e+02 +14 5941 3.267000e+02 3.291800e+02 +7 5942 2.651500e+02 5.333900e+02 +9 5942 -3.032100e+02 4.632200e+02 +7 5943 -4.666003e+01 5.347200e+02 +10 5943 -5.071600e+02 -2.072200e+02 +7 5944 1.108960e+03 5.355200e+02 +10 5944 4.566599e+02 -2.191801e+02 +12 5944 -5.091003e+01 -3.079700e+02 +18 5944 1.488600e+02 1.672900e+02 +20 5944 1.314100e+02 -5.112000e+01 +7 5945 -5.205000e+02 5.365901e+02 +9 5945 -1.463410e+03 5.009600e+02 +18 5945 -1.179980e+03 2.130801e+02 +20 5945 -1.014360e+03 -1.601001e+01 +7 5946 2.994995e+01 5.410601e+02 +10 5946 -4.326200e+02 -2.028500e+02 +12 5946 -1.076950e+03 -2.933400e+02 +14 5946 4.761200e+02 3.464800e+02 +16 5946 2.575000e+02 4.954500e+02 +7 5947 -3.395601e+02 5.475500e+02 +10 5947 -8.121800e+02 -1.902700e+02 +11 5947 -4.872400e+02 4.261300e+02 +19 5947 1.354970e+03 4.989800e+02 +7 5948 -3.945100e+02 5.496000e+02 +9 5948 -1.257930e+03 5.105400e+02 +7 5949 -3.038900e+02 5.548500e+02 +10 5949 -7.801500e+02 -1.854600e+02 +7 5950 1.097350e+03 5.591799e+02 +9 5950 6.556799e+02 5.099900e+02 +10 5950 4.460701e+02 -1.995100e+02 +12 5950 -6.116003e+01 -2.858500e+02 +18 5950 1.399600e+02 1.848401e+02 +7 5951 -3.201000e+02 5.798300e+02 +10 5951 -7.960700e+02 -1.610300e+02 +16 5951 2.543005e+01 5.121400e+02 +19 5951 1.388940e+03 5.399000e+02 +7 5952 -8.742004e+01 5.806100e+02 +10 5952 -5.559000e+02 -1.656801e+02 +14 5952 3.956100e+02 3.611500e+02 +16 5952 1.803800e+02 5.212700e+02 +7 5953 -3.644700e+02 5.915400e+02 +9 5953 -1.215680e+03 5.671300e+02 +11 5953 -5.212700e+02 4.831700e+02 +16 5953 -1.066998e+01 5.199900e+02 +20 5953 -8.778900e+02 1.558002e+01 +7 5954 -1.144800e+02 5.961200e+02 +9 5954 -8.194400e+02 5.542000e+02 +7 5955 4.948700e+02 6.034100e+02 +10 5955 2.243900e+02 -1.477800e+02 +12 5955 -4.829100e+02 -3.704600e+02 +16 5955 4.260800e+02 5.690300e+02 +18 5955 -6.696997e+01 1.191000e+02 +20 5955 -4.525000e+01 -9.544995e+01 +7 5956 4.733900e+02 6.060601e+02 +10 5956 1.931500e+02 -1.470400e+02 +7 5957 -5.153000e+02 6.138400e+02 +9 5957 -1.467630e+03 6.100801e+02 +7 5958 -5.143400e+02 6.186600e+02 +9 5958 -1.464580e+03 6.170200e+02 +10 5958 -9.876700e+02 -1.211600e+02 +11 5958 -7.604200e+02 5.314900e+02 +19 5958 1.137590e+03 5.541899e+02 +7 5959 -5.070000e+02 6.201700e+02 +10 5959 -9.798200e+02 -1.198199e+02 +11 5959 -7.487600e+02 5.326000e+02 +7 5960 -5.070000e+02 6.201700e+02 +9 5960 -1.451900e+03 6.183301e+02 +10 5960 -9.798200e+02 -1.198199e+02 +11 5960 -7.487600e+02 5.326000e+02 +16 5960 -1.045800e+02 5.362200e+02 +7 5961 -4.775900e+02 6.266400e+02 +9 5961 -1.401990e+03 6.245901e+02 +11 5961 -6.998000e+02 5.384700e+02 +20 5961 -9.772600e+02 4.931006e+01 +7 5962 -3.677500e+02 6.289399e+02 +10 5962 -8.439900e+02 -1.159700e+02 +7 5963 -1.169600e+03 7.748600e+02 +10 5963 3.012500e+02 1.957000e+02 +7 5964 6.943994e+01 6.359998e+01 +10 5964 -1.071600e+02 -6.447400e+02 +7 5965 1.098840e+03 1.539000e+02 +9 5965 7.373401e+02 -2.969971e+00 +10 5965 5.147500e+02 -5.402300e+02 +12 5965 -4.242004e+01 -6.826100e+02 +20 5965 1.605300e+02 -3.070400e+02 +7 5966 1.865200e+02 1.590701e+02 +9 5966 -3.806801e+02 -1.782996e+01 +11 5966 2.718800e+02 -7.144000e+01 +12 5966 -9.274800e+02 -6.838600e+02 +18 5966 -5.159600e+02 -1.272200e+02 +7 5967 1.344910e+03 1.666200e+02 +9 5967 9.818201e+02 2.535999e+01 +10 5967 6.815601e+02 -5.243300e+02 +18 5967 3.305900e+02 -1.165800e+02 +20 5967 2.900601e+02 -2.936801e+02 +7 5968 1.699900e+02 1.731000e+02 +9 5968 -4.005300e+02 -8.800049e-01 +7 5969 2.723199e+02 1.743600e+02 +10 5969 -2.189301e+02 -5.373900e+02 +7 5970 1.176830e+03 2.144299e+02 +9 5970 8.091699e+02 7.302002e+01 +7 5971 1.315910e+03 2.438700e+02 +9 5971 9.453999e+02 1.171300e+02 +7 5972 3.672800e+02 2.482200e+02 +10 5972 -1.502500e+02 -4.694900e+02 +7 5973 1.181510e+03 2.566899e+02 +9 5973 8.123301e+02 1.231200e+02 +7 5974 1.150090e+03 2.565801e+02 +9 5974 7.779399e+02 1.221801e+02 +12 5974 -3.002930e-02 -5.853900e+02 +18 5974 2.066300e+02 -5.465002e+01 +7 5975 1.346430e+03 2.571500e+02 +9 5975 9.802200e+02 1.338700e+02 +10 5975 6.772800e+02 -4.479200e+02 +12 5975 1.683400e+02 -5.776200e+02 +7 5976 2.604500e+02 2.587500e+02 +10 5976 -2.280900e+02 -4.603600e+02 +13 5976 -1.715040e+03 1.818500e+02 +18 5976 -4.627200e+02 -4.670996e+01 +7 5977 1.128660e+03 2.614600e+02 +9 5977 7.512900e+02 1.281500e+02 +13 5977 1.677420e+03 1.373101e+02 +7 5978 1.122850e+03 2.615100e+02 +9 5978 7.452700e+02 1.280300e+02 +12 5978 -2.444995e+01 -5.804399e+02 +13 5978 1.656790e+03 1.373301e+02 +17 5978 -4.889100e+02 2.730200e+02 +7 5979 2.731500e+02 2.612300e+02 +10 5979 -2.190900e+02 -4.580500e+02 +11 5979 3.560500e+02 5.770001e+01 +12 5979 -8.419100e+02 -5.769800e+02 +7 5980 1.117450e+03 2.895100e+02 +9 5980 7.378201e+02 1.620901e+02 +10 5980 5.119600e+02 -4.242700e+02 +12 5980 -2.941003e+01 -5.539500e+02 +13 5980 1.635710e+03 2.459800e+02 +17 5980 -5.020699e+02 3.373500e+02 +7 5981 3.479900e+02 2.926899e+02 +9 5981 -2.202600e+02 1.633000e+02 +7 5982 1.172340e+03 3.037100e+02 +9 5982 8.002600e+02 1.793101e+02 +10 5982 5.544199e+02 -4.115601e+02 +12 5982 1.816003e+01 -5.412600e+02 +18 5982 2.202500e+02 -2.008997e+01 +7 5983 1.165640e+03 3.036699e+02 +9 5983 7.919800e+02 1.793600e+02 +10 5983 5.494500e+02 -4.118199e+02 +7 5984 1.159300e+03 3.036300e+02 +9 5984 7.855300e+02 1.789500e+02 +10 5984 5.445500e+02 -4.119900e+02 +12 5984 7.000000e+00 -5.414700e+02 +7 5985 1.156450e+03 3.065100e+02 +10 5985 5.422000e+02 -4.097300e+02 +12 5985 4.099976e+00 -5.389000e+02 +18 5985 2.098000e+02 -1.781006e+01 +7 5986 1.243910e+03 3.073201e+02 +10 5986 6.118000e+02 -4.082600e+02 +12 5986 8.142004e+01 -5.389200e+02 +20 5986 2.380500e+02 -2.100000e+02 +7 5987 1.004220e+03 3.128700e+02 +9 5987 6.087000e+02 1.870500e+02 +7 5988 1.358870e+03 3.151599e+02 +9 5988 9.919900e+02 2.025000e+02 +18 5988 3.391300e+02 -7.819946e+00 +7 5989 1.640300e+02 3.157900e+02 +9 5989 -4.112900e+02 1.804900e+02 +10 5989 -3.098000e+02 -4.084100e+02 +7 5990 1.237400e+02 3.159900e+02 +10 5990 -3.461200e+02 -4.080900e+02 +12 5990 -9.867000e+02 -5.240900e+02 +7 5991 1.050720e+03 3.173000e+02 +9 5991 6.650000e+02 1.933500e+02 +13 5991 1.410620e+03 3.589500e+02 +17 5991 -6.155900e+02 4.035500e+02 +7 5992 1.089570e+03 3.294399e+02 +9 5992 7.035400e+02 2.097000e+02 +7 5993 1.152090e+03 3.327400e+02 +9 5993 7.775000e+02 2.137000e+02 +7 5994 2.345400e+02 3.415200e+02 +10 5994 -2.494100e+02 -3.851899e+02 +12 5994 -8.754600e+02 -4.978800e+02 +7 5995 2.345400e+02 3.415200e+02 +10 5995 -2.494100e+02 -3.851899e+02 +12 5995 -8.754600e+02 -4.978800e+02 +7 5996 1.268700e+02 3.477700e+02 +9 5996 -4.579399e+02 2.205601e+02 +11 5996 1.991200e+02 1.574400e+02 +7 5997 1.101260e+03 3.545100e+02 +10 5997 4.963000e+02 -3.697000e+02 +12 5997 -4.490002e+01 -4.941801e+02 +18 5997 1.712700e+02 1.812000e+01 +20 5997 1.529900e+02 -1.786300e+02 +7 5998 -3.642900e+02 3.621400e+02 +9 5998 -1.198160e+03 2.529900e+02 +7 5999 1.053400e+02 3.648000e+02 +11 5999 1.739200e+02 1.775700e+02 +7 6000 1.180710e+03 3.720400e+02 +9 6000 8.080000e+02 2.600701e+02 +7 6001 -4.860900e+02 3.770300e+02 +10 6001 -9.635200e+02 -3.448000e+02 +11 6001 -6.937800e+02 2.112400e+02 +18 6001 -1.145310e+03 7.291992e+01 +20 6001 -9.860200e+02 -1.371300e+02 +7 6002 1.125640e+03 3.870000e+02 +9 6002 7.442400e+02 2.780701e+02 +10 6002 5.135801e+02 -3.421200e+02 +12 6002 -2.408997e+01 -4.646700e+02 +13 6002 1.661000e+03 6.134000e+02 +17 6002 -4.906300e+02 5.559000e+02 +20 6002 1.672100e+02 -1.591700e+02 +7 6003 1.141130e+03 3.879800e+02 +10 6003 5.260500e+02 -3.416200e+02 +12 6003 -1.059998e+01 -4.640699e+02 +17 6003 -4.571500e+02 5.575400e+02 +18 6003 1.983600e+02 4.147998e+01 +7 6004 1.209110e+03 3.886100e+02 +9 6004 8.405300e+02 2.804399e+02 +10 6004 5.805100e+02 -3.400900e+02 +12 6004 4.906995e+01 -4.644500e+02 +18 6004 2.460400e+02 4.119995e+01 +7 6005 1.267600e+02 3.884199e+02 +11 6005 1.982300e+02 2.074200e+02 +7 6006 1.144410e+03 3.906400e+02 +9 6006 7.658799e+02 2.820901e+02 +10 6006 5.283201e+02 -3.388300e+02 +12 6006 -7.989990e+00 -4.614600e+02 +17 6006 -4.506899e+02 5.631000e+02 +18 6006 2.002600e+02 4.443005e+01 +7 6007 1.266480e+03 3.929000e+02 +9 6007 9.066001e+02 2.852000e+02 +10 6007 6.261201e+02 -3.358400e+02 +7 6008 1.266480e+03 3.929000e+02 +9 6008 9.066001e+02 2.852000e+02 +10 6008 6.261201e+02 -3.358400e+02 +7 6009 2.015601e+02 3.945701e+02 +10 6009 -2.774000e+02 -3.368101e+02 +11 6009 2.854500e+02 2.157700e+02 +12 6009 -9.055000e+02 -4.444500e+02 +18 6009 -5.027600e+02 6.016992e+01 +20 6009 -4.262700e+02 -1.464399e+02 +7 6010 1.220220e+03 3.992800e+02 +10 6010 5.884800e+02 -3.304301e+02 +18 6010 2.528900e+02 4.946997e+01 +20 6010 2.225200e+02 -1.506899e+02 +7 6011 1.099660e+03 3.996599e+02 +9 6011 7.121499e+02 2.941300e+02 +7 6012 1.094910e+03 3.995801e+02 +9 6012 7.070100e+02 2.941799e+02 +7 6013 1.704700e+02 4.065701e+02 +11 6013 2.492800e+02 2.305300e+02 +7 6014 2.066300e+02 4.092400e+02 +10 6014 -2.654800e+02 -3.250900e+02 +12 6014 -8.919300e+02 -4.316801e+02 +7 6015 1.049540e+03 4.116799e+02 +9 6015 6.606101e+02 3.056000e+02 +10 6015 4.548201e+02 -3.216200e+02 +12 6015 -9.145996e+01 -4.421100e+02 +13 6015 1.400440e+03 7.192900e+02 +17 6015 -6.265200e+02 6.195000e+02 +20 6015 1.229500e+02 -1.432400e+02 +7 6016 1.050030e+03 4.204299e+02 +9 6016 6.606699e+02 3.158700e+02 +7 6017 2.157400e+02 4.288900e+02 +10 6017 -2.660200e+02 -3.057500e+02 +7 6018 -4.830600e+02 4.376799e+02 +9 6018 -1.398320e+03 3.628800e+02 +10 6018 -9.601500e+02 -2.882100e+02 +16 6018 -9.048999e+01 4.029000e+02 +18 6018 -1.142710e+03 1.254000e+02 +20 6018 -9.835100e+02 -9.185999e+01 +7 6019 9.870300e+02 4.462200e+02 +9 6019 5.855300e+02 3.475300e+02 +10 6019 4.011899e+02 -2.931600e+02 +12 6019 -1.488000e+02 -4.094301e+02 +18 6019 9.037000e+01 8.605005e+01 +7 6020 -2.685100e+02 4.472100e+02 +9 6020 -1.044440e+03 3.635801e+02 +11 6020 -3.569700e+02 2.903300e+02 +7 6021 1.033840e+03 4.476400e+02 +9 6021 6.406299e+02 3.493700e+02 +13 6021 1.339620e+03 8.579900e+02 +7 6022 -3.284900e+02 4.559099e+02 +9 6022 -1.141370e+03 3.781899e+02 +7 6023 -8.612100e+02 4.582800e+02 +11 6023 -9.744700e+02 2.783000e+02 +16 6023 -4.247400e+02 4.074399e+02 +18 6023 -1.365270e+03 1.202400e+02 +7 6024 -2.402500e+02 4.742300e+02 +11 6024 -3.128600e+02 3.225400e+02 +12 6024 -1.391910e+03 -3.416600e+02 +7 6025 -3.512200e+02 4.737700e+02 +9 6025 -1.179300e+03 4.045601e+02 +11 6025 -4.848100e+02 3.287800e+02 +19 6025 1.332260e+03 4.051400e+02 +7 6026 1.311700e+02 4.799500e+02 +10 6026 -3.398000e+02 -2.596500e+02 +11 6026 2.028600e+02 3.194600e+02 +18 6026 -5.569200e+02 1.276899e+02 +7 6027 1.559600e+02 4.832100e+02 +10 6027 -3.166600e+02 -2.569900e+02 +7 6028 7.104004e+01 4.840000e+02 +11 6028 1.298500e+02 3.236800e+02 +7 6029 -2.758400e+02 4.853700e+02 +9 6029 -1.055700e+03 4.141100e+02 +7 6030 2.448900e+02 4.859099e+02 +10 6030 -2.419800e+02 -2.560300e+02 +7 6031 1.974399e+02 4.877400e+02 +9 6031 -3.747800e+02 4.002000e+02 +11 6031 2.792500e+02 3.304600e+02 +7 6032 1.864600e+02 4.880701e+02 +11 6032 2.664000e+02 3.309700e+02 +7 6033 2.568400e+02 4.890601e+02 +9 6033 -3.083400e+02 4.041100e+02 +7 6034 1.109670e+03 4.924700e+02 +9 6034 6.731599e+02 4.279900e+02 +12 6034 -4.954004e+01 -3.472700e+02 +17 6034 -7.765200e+02 7.997500e+02 +18 6034 1.499200e+02 1.353401e+02 +7 6035 -3.912400e+02 4.924199e+02 +9 6035 -1.244130e+03 4.315801e+02 +11 6035 -5.464500e+02 3.546899e+02 +7 6036 -3.912400e+02 4.924199e+02 +11 6036 -5.465400e+02 3.547500e+02 +7 6037 -4.735000e+02 4.951400e+02 +9 6037 -1.383080e+03 4.414399e+02 +18 6037 -1.130580e+03 1.742400e+02 +20 6037 -9.721000e+02 -4.955005e+01 +7 6038 -3.916200e+02 4.960801e+02 +9 6038 -1.243910e+03 4.369299e+02 +11 6038 -5.462100e+02 3.598700e+02 +7 6039 1.019550e+03 4.966899e+02 +9 6039 5.647900e+02 4.345801e+02 +12 6039 -1.316600e+02 -3.421400e+02 +7 6040 -3.582600e+02 4.972800e+02 +9 6040 -1.190540e+03 4.359800e+02 +11 6040 -4.954400e+02 3.586000e+02 +18 6040 -1.011640e+03 1.673101e+02 +19 6040 1.321410e+03 4.357200e+02 +7 6041 -3.825100e+02 4.978900e+02 +9 6041 -1.230230e+03 4.387600e+02 +19 6041 1.290470e+03 4.313000e+02 +7 6042 1.180100e+03 5.070300e+02 +10 6042 5.150701e+02 -2.431000e+02 +12 6042 1.368994e+01 -3.368400e+02 +18 6042 2.007400e+02 1.432000e+02 +7 6043 1.108290e+03 5.082600e+02 +10 6043 4.573601e+02 -2.416899e+02 +12 6043 -5.104004e+01 -3.336700e+02 +18 6043 1.488101e+02 1.460601e+02 +7 6044 -2.628700e+02 5.126699e+02 +9 6044 -1.035370e+03 4.498101e+02 +11 6044 -3.483300e+02 3.722800e+02 +7 6045 -2.247800e+02 5.184500e+02 +11 6045 -2.904200e+02 3.771600e+02 +7 6046 -2.340000e+02 5.211500e+02 +9 6046 -9.885600e+02 4.594700e+02 +11 6046 -3.049500e+02 3.814500e+02 +7 6047 -2.269399e+02 5.216799e+02 +11 6047 -2.933300e+02 3.820701e+02 +7 6048 1.069550e+03 5.225000e+02 +9 6048 6.130601e+02 4.652600e+02 +10 6048 4.179600e+02 -2.295800e+02 +7 6049 -5.462500e+02 5.229900e+02 +9 6049 -1.505980e+03 4.845601e+02 +19 6049 1.094980e+03 4.323101e+02 +7 6050 -5.158700e+02 5.245000e+02 +9 6050 -1.454820e+03 4.849600e+02 +11 6050 -7.479700e+02 4.052400e+02 +7 6051 -5.158700e+02 5.245000e+02 +9 6051 -1.454820e+03 4.849600e+02 +11 6051 -7.479700e+02 4.052400e+02 +7 6052 -5.017200e+02 5.274099e+02 +10 6052 -9.751600e+02 -2.048600e+02 +7 6053 -5.542500e+02 5.298301e+02 +10 6053 -1.029240e+03 -2.010800e+02 +11 6053 -8.107400e+02 4.158700e+02 +20 6053 -1.046500e+03 -1.865997e+01 +7 6054 -7.708800e+02 5.340400e+02 +11 6054 -9.518100e+02 3.911500e+02 +7 6055 2.662500e+02 5.370901e+02 +10 6055 -2.262700e+02 -2.103600e+02 +7 6056 1.112150e+03 5.392000e+02 +9 6056 6.744900e+02 4.849199e+02 +12 6056 -4.757996e+01 -3.053500e+02 +18 6056 1.519700e+02 1.686599e+02 +7 6057 1.128100e+03 5.393800e+02 +9 6057 6.931299e+02 4.855000e+02 +7 6058 1.159670e+03 5.402600e+02 +10 6058 4.964800e+02 -2.158400e+02 +12 6058 -5.709961e+00 -3.059000e+02 +7 6059 -3.278000e+02 5.446100e+02 +10 6059 -8.009700e+02 -1.932400e+02 +7 6060 -3.278000e+02 5.446100e+02 +9 6060 -1.160560e+03 5.076100e+02 +10 6060 -8.009700e+02 -1.932400e+02 +11 6060 -4.718100e+02 4.221799e+02 +7 6061 2.274200e+02 5.450701e+02 +9 6061 -3.437600e+02 4.741300e+02 +7 6062 7.633997e+01 5.449700e+02 +9 6062 -5.306600e+02 4.714900e+02 +10 6062 -3.920400e+02 -2.017100e+02 +11 6062 1.301801e+02 3.965800e+02 +16 6062 2.907100e+02 4.987000e+02 +7 6063 -5.304200e+02 5.512300e+02 +10 6063 -1.004030e+03 -1.828800e+02 +7 6064 1.798300e+02 5.583800e+02 +10 6064 -2.963199e+02 -1.902200e+02 +7 6065 1.057010e+03 5.640200e+02 +9 6065 6.093201e+02 5.164000e+02 +7 6066 -3.302300e+02 5.654500e+02 +10 6066 -8.037700e+02 -1.740000e+02 +11 6066 -4.770700e+02 4.498500e+02 +16 6066 1.490002e+01 5.020200e+02 +18 6066 -9.946100e+02 2.273500e+02 +19 6066 1.369090e+03 5.231100e+02 +7 6067 5.963600e+02 5.818800e+02 +10 6067 2.984500e+02 -1.679200e+02 +7 6068 -3.564001e+01 5.898800e+02 +10 6068 -5.312600e+02 -1.613500e+02 +7 6069 4.636801e+02 5.954700e+02 +10 6069 1.860200e+02 -1.563300e+02 +16 6069 4.085100e+02 5.624299e+02 +7 6070 -3.433199e+02 6.049100e+02 +10 6070 -8.157500e+02 -1.380400e+02 +20 6070 -8.643400e+02 2.627002e+01 +7 6071 -1.720100e+02 6.098000e+02 +10 6071 -6.370699e+02 -1.385400e+02 +7 6072 -1.720100e+02 6.098000e+02 +9 6072 -9.046400e+02 5.733700e+02 +10 6072 -6.370699e+02 -1.385400e+02 +7 6073 -7.250000e+01 6.117200e+02 +9 6073 -7.703400e+02 5.764700e+02 +10 6073 -5.444800e+02 -1.381200e+02 +11 6073 -1.008400e+02 4.943700e+02 +18 6073 -7.471800e+02 2.477800e+02 +7 6074 -8.825000e+01 6.312700e+02 +9 6074 -7.885100e+02 6.009199e+02 +11 6074 -1.170000e+02 5.180300e+02 +7 6075 -1.763101e+02 6.408400e+02 +11 6075 -2.325700e+02 5.301500e+02 +12 6075 -1.312470e+03 -1.714500e+02 +18 6075 -8.342000e+02 2.742500e+02 +20 6075 -7.138600e+02 3.778003e+01 +7 6076 -1.281899e+02 6.510400e+02 +9 6076 -8.385500e+02 6.268401e+02 +10 6076 -5.923600e+02 -1.014900e+02 +11 6076 -1.634600e+02 5.423600e+02 +12 6076 -1.255270e+03 -1.662000e+02 +16 6076 1.486500e+02 5.723900e+02 +18 6076 -7.890800e+02 2.803301e+02 +20 6076 -6.735500e+02 4.208008e+01 +7 6077 1.287700e+02 8.708008e+01 +11 6077 7.825100e+02 -2.309100e+02 +7 6078 1.287700e+02 8.708008e+01 +11 6078 7.825100e+02 -2.309100e+02 +7 6079 1.331660e+03 1.409800e+02 +9 6079 9.670400e+02 -5.579956e+00 +7 6080 1.317310e+03 1.502000e+02 +9 6080 9.497400e+02 5.599976e+00 +12 6080 1.463300e+02 -6.770300e+02 +7 6081 1.424301e+02 1.703101e+02 +10 6081 -3.282700e+02 -5.420601e+02 +7 6082 1.266270e+03 1.731799e+02 +9 6082 9.134199e+02 2.490002e+01 +7 6083 1.151040e+03 1.727300e+02 +9 6083 7.881899e+02 2.022998e+01 +7 6084 1.038860e+03 1.728800e+02 +9 6084 6.556101e+02 1.870996e+01 +17 6084 -6.333800e+02 7.079004e+01 +7 6085 2.034900e+02 1.761100e+02 +10 6085 -2.744900e+02 -5.362500e+02 +7 6086 1.099270e+03 1.778101e+02 +10 6086 5.144600e+02 -5.197800e+02 +7 6087 1.061190e+03 1.891599e+02 +9 6087 6.813000e+02 3.881006e+01 +7 6088 1.135220e+03 2.014199e+02 +9 6088 7.669199e+02 5.447998e+01 +10 6088 5.341699e+02 -4.989200e+02 +12 6088 -1.169995e+01 -6.379000e+02 +7 6089 1.177660e+03 2.254199e+02 +9 6089 8.086201e+02 8.694995e+01 +10 6089 5.628101e+02 -4.772700e+02 +20 6089 1.998900e+02 -2.585100e+02 +7 6090 1.174680e+03 2.375400e+02 +9 6090 8.048201e+02 1.006200e+02 +7 6091 1.174680e+03 2.375400e+02 +9 6091 8.048201e+02 1.006200e+02 +7 6092 9.248999e+01 2.389299e+02 +9 6092 -4.990900e+02 8.094995e+01 +7 6093 1.352750e+03 2.572300e+02 +9 6093 9.867100e+02 1.339500e+02 +12 6093 1.746700e+02 -5.774600e+02 +7 6094 1.323950e+03 2.570400e+02 +9 6094 9.534500e+02 1.335400e+02 +12 6094 1.486000e+02 -5.778700e+02 +7 6095 -7.969500e+02 2.581500e+02 +11 6095 -9.064600e+02 2.694000e+01 +7 6096 1.205420e+03 2.597600e+02 +10 6096 5.845100e+02 -4.484200e+02 +12 6096 4.883997e+01 -5.828600e+02 +18 6096 2.454100e+02 -5.295996e+01 +7 6097 1.326400e+02 2.607000e+02 +9 6097 -4.488500e+02 1.097500e+02 +7 6098 1.033200e+03 2.620100e+02 +9 6098 6.452100e+02 1.254900e+02 +7 6099 1.266050e+03 2.629800e+02 +9 6099 9.099800e+02 1.311000e+02 +12 6099 1.019399e+02 -5.791600e+02 +18 6099 2.883101e+02 -5.034998e+01 +7 6100 1.214500e+03 2.638900e+02 +9 6100 8.505200e+02 1.317400e+02 +12 6100 5.583997e+01 -5.784301e+02 +7 6101 1.046590e+03 2.650701e+02 +9 6101 6.610300e+02 1.300601e+02 +10 6101 4.588999e+02 -4.457000e+02 +13 6101 1.394320e+03 1.583500e+02 +18 6101 1.351899e+02 -4.757996e+01 +7 6102 1.332040e+03 3.054099e+02 +9 6102 9.611201e+02 1.916500e+02 +7 6103 4.135699e+02 3.059299e+02 +9 6103 -1.672700e+02 1.889600e+02 +7 6104 1.090060e+03 3.113500e+02 +9 6104 7.041299e+02 1.876500e+02 +7 6105 1.047810e+03 3.199399e+02 +9 6105 6.614600e+02 1.985901e+02 +12 6105 -9.167004e+01 -5.274200e+02 +17 6105 -6.246200e+02 4.124299e+02 +7 6106 1.353740e+03 3.216799e+02 +9 6106 9.857400e+02 2.099099e+02 +7 6107 1.047930e+03 3.282400e+02 +9 6107 6.608899e+02 2.059600e+02 +12 6107 -9.204004e+01 -5.194700e+02 +13 6107 1.396350e+03 4.001799e+02 +17 6107 -6.258199e+02 4.283101e+02 +7 6108 1.681700e+02 3.283201e+02 +9 6108 -4.070500e+02 1.969500e+02 +7 6109 1.681700e+02 3.283201e+02 +9 6109 -4.070500e+02 1.969500e+02 +7 6110 1.265900e+03 3.340000e+02 +10 6110 6.284700e+02 -3.844900e+02 +7 6111 1.354510e+03 3.437800e+02 +9 6111 9.863799e+02 2.368700e+02 +7 6112 1.268400e+02 3.440901e+02 +9 6112 -4.578300e+02 2.157200e+02 +7 6113 8.672998e+01 3.438600e+02 +11 6113 1.502300e+02 1.520100e+02 +7 6114 1.129400e+03 3.495100e+02 +9 6114 7.494700e+02 2.336799e+02 +7 6115 1.205450e+03 3.508600e+02 +9 6115 8.382500e+02 2.353101e+02 +7 6116 2.554800e+02 3.629199e+02 +9 6116 -3.095200e+02 2.449800e+02 +7 6117 1.267430e+03 3.766300e+02 +9 6117 9.080200e+02 2.661000e+02 +12 6117 1.000601e+02 -4.752400e+02 +7 6118 1.180010e+03 3.787000e+02 +9 6118 8.073201e+02 2.683301e+02 +7 6119 1.115860e+03 3.800500e+02 +9 6119 7.327800e+02 2.699199e+02 +13 6119 1.623500e+03 5.899299e+02 +7 6120 -2.780500e+02 3.800100e+02 +11 6120 -3.705700e+02 2.062100e+02 +7 6121 1.233700e+03 3.823500e+02 +9 6121 8.687200e+02 2.724299e+02 +7 6122 1.233700e+03 3.823500e+02 +9 6122 8.687200e+02 2.724299e+02 +7 6123 1.224100e+03 3.859399e+02 +9 6123 8.571899e+02 2.775500e+02 +12 6123 6.242004e+01 -4.661600e+02 +7 6124 1.241010e+03 3.883201e+02 +9 6124 8.770300e+02 2.807000e+02 +12 6124 7.701001e+01 -4.641100e+02 +7 6125 2.991300e+02 3.927800e+02 +11 6125 3.785800e+02 2.215100e+02 +7 6126 2.991300e+02 3.927800e+02 +11 6126 3.785800e+02 2.215100e+02 +7 6127 1.105990e+03 3.968201e+02 +9 6127 7.197000e+02 2.907300e+02 +13 6127 1.583540e+03 6.559500e+02 +17 6127 -5.399800e+02 5.810000e+02 +7 6128 1.228230e+03 3.989299e+02 +9 6128 8.603701e+02 2.934299e+02 +7 6129 1.674800e+02 3.990500e+02 +9 6129 -4.085500e+02 2.867900e+02 +7 6130 1.248670e+03 4.001699e+02 +9 6130 8.845300e+02 2.947300e+02 +7 6131 1.053600e+02 4.016100e+02 +11 6131 1.729700e+02 2.225800e+02 +7 6132 -2.569800e+02 4.029000e+02 +9 6132 -1.024370e+03 3.029099e+02 +7 6133 -7.505800e+02 4.042100e+02 +10 6133 -1.168680e+03 -3.131100e+02 +11 6133 -8.724000e+02 2.179900e+02 +7 6134 -2.626200e+02 4.065400e+02 +11 6134 -3.450600e+02 2.385900e+02 +7 6135 -4.900700e+02 4.063401e+02 +9 6135 -1.408920e+03 3.206300e+02 +11 6135 -7.029500e+02 2.499200e+02 +7 6136 1.052240e+03 4.139900e+02 +9 6136 6.635500e+02 3.081699e+02 +12 6136 -8.856995e+01 -4.399200e+02 +7 6137 -5.036200e+02 4.144900e+02 +9 6137 -1.430920e+03 3.324700e+02 +7 6138 9.841299e+02 4.191599e+02 +9 6138 5.826699e+02 3.144600e+02 +7 6139 -4.832500e+02 4.197700e+02 +9 6139 -1.397360e+03 3.380500e+02 +19 6139 1.167560e+03 3.119099e+02 +7 6140 1.250190e+03 4.209600e+02 +9 6140 8.846499e+02 3.196100e+02 +12 6140 8.401001e+01 -4.339200e+02 +7 6141 9.676001e+01 4.239600e+02 +11 6141 1.630400e+02 2.500700e+02 +7 6142 -4.072500e+02 4.292400e+02 +11 6142 -5.713800e+02 2.748500e+02 +7 6143 1.027410e+03 4.299399e+02 +9 6143 6.345400e+02 3.274800e+02 +12 6143 -1.117700e+02 -4.246700e+02 +7 6144 1.150440e+03 4.395400e+02 +10 6144 5.272800e+02 -2.976899e+02 +12 6144 -4.550049e+00 -4.140699e+02 +18 6144 2.018900e+02 8.184009e+01 +7 6145 -3.181600e+02 4.623500e+02 +11 6145 -4.324800e+02 3.129300e+02 +7 6146 3.617100e+02 4.633101e+02 +10 6146 -1.732800e+02 -2.776200e+02 +12 6146 -7.703300e+02 -3.595699e+02 +13 6146 -1.461560e+03 9.908401e+02 +7 6147 1.524000e+02 4.694700e+02 +9 6147 -4.278600e+02 3.764299e+02 +7 6148 2.124700e+02 4.737900e+02 +9 6148 -3.578700e+02 3.840300e+02 +7 6149 -2.932100e+02 4.743700e+02 +9 6149 -1.084800e+03 4.004700e+02 +7 6150 -3.556300e+02 4.751599e+02 +9 6150 -1.186050e+03 4.036000e+02 +7 6151 1.354004e+01 4.787700e+02 +11 6151 5.543005e+01 3.174900e+02 +7 6152 -4.743600e+02 4.794199e+02 +11 6152 -6.791500e+02 3.434399e+02 +7 6153 6.206400e+02 4.801000e+02 +9 6153 5.057000e+02 2.534800e+02 +7 6154 -2.937200e+02 4.801699e+02 +9 6154 -1.085320e+03 4.099299e+02 +7 6155 2.113199e+02 4.806500e+02 +9 6155 -3.587900e+02 3.913600e+02 +18 6155 -4.958700e+02 1.280000e+02 +7 6156 5.305005e+01 4.838000e+02 +9 6156 -5.546700e+02 3.945100e+02 +7 6157 -2.790900e+02 4.845601e+02 +11 6157 -3.730300e+02 3.376500e+02 +18 6157 -9.319300e+02 1.514600e+02 +7 6158 1.105660e+03 4.859000e+02 +9 6158 6.683701e+02 4.199399e+02 +7 6159 2.470400e+02 4.886200e+02 +11 6159 3.310400e+02 3.340200e+02 +7 6160 2.366400e+02 4.932000e+02 +9 6160 -3.301100e+02 4.079800e+02 +7 6161 1.032100e+02 4.986100e+02 +9 6161 -4.901200e+02 4.131599e+02 +11 6161 1.699700e+02 3.419800e+02 +7 6162 -2.795200e+02 5.097000e+02 +9 6162 -1.062270e+03 4.472000e+02 +7 6163 8.758997e+01 5.114000e+02 +9 6163 -5.117900e+02 4.302400e+02 +11 6163 1.489301e+02 3.580000e+02 +7 6164 -2.379800e+02 5.147200e+02 +9 6164 -9.957900e+02 4.512400e+02 +11 6164 -3.098600e+02 3.737600e+02 +7 6165 -2.220200e+02 5.157300e+02 +9 6165 -9.697600e+02 4.506699e+02 +11 6165 -2.864800e+02 3.732300e+02 +7 6166 9.062000e+01 5.189700e+02 +9 6166 -5.086899e+02 4.396599e+02 +11 6166 1.522000e+02 3.673300e+02 +7 6167 -2.183600e+02 5.204099e+02 +11 6167 -2.816300e+02 3.787500e+02 +7 6168 1.013260e+03 5.225500e+02 +9 6168 5.568301e+02 4.665200e+02 +7 6169 1.079100e+03 5.259500e+02 +9 6169 6.350300e+02 4.701899e+02 +7 6170 -5.325300e+02 5.258600e+02 +9 6170 -1.482750e+03 4.871100e+02 +11 6170 -7.752100e+02 4.077700e+02 +16 6170 -1.251400e+02 4.654500e+02 +18 6170 -1.193510e+03 2.042900e+02 +20 6170 -1.026240e+03 -2.353003e+01 +7 6171 6.281006e+01 5.277000e+02 +9 6171 -5.468800e+02 4.513900e+02 +7 6172 1.107700e+03 5.296599e+02 +9 6172 6.691599e+02 4.733000e+02 +10 6172 4.561399e+02 -2.240000e+02 +12 6172 -5.135999e+01 -3.139000e+02 +17 6172 -7.837300e+02 8.837600e+02 +18 6172 1.486000e+02 1.620901e+02 +7 6173 1.135340e+03 5.307200e+02 +9 6173 7.037900e+02 4.748101e+02 +7 6174 -4.956000e+02 5.328000e+02 +11 6174 -7.147900e+02 4.144399e+02 +7 6175 -2.108900e+02 5.358500e+02 +9 6175 -9.519900e+02 4.770701e+02 +11 6175 -2.695000e+02 3.985400e+02 +12 6175 -1.353020e+03 -2.801100e+02 +7 6176 -2.108900e+02 5.358500e+02 +9 6176 -9.519900e+02 4.770701e+02 +11 6176 -2.695000e+02 3.985400e+02 +7 6177 1.369940e+03 5.380400e+02 +9 6177 8.859099e+02 5.313101e+02 +7 6178 1.099320e+03 5.391699e+02 +10 6178 4.489900e+02 -2.161000e+02 +12 6178 -5.923999e+01 -3.051200e+02 +7 6179 1.099320e+03 5.391699e+02 +10 6179 4.489900e+02 -2.161000e+02 +7 6180 2.190800e+02 5.433000e+02 +9 6180 -3.508199e+02 4.715601e+02 +11 6180 3.021300e+02 3.998700e+02 +7 6181 6.115002e+01 5.453900e+02 +9 6181 -5.490700e+02 4.739800e+02 +7 6182 1.260960e+03 5.470300e+02 +9 6182 8.486101e+02 4.923700e+02 +7 6183 1.252820e+03 5.469900e+02 +10 6183 5.697500e+02 -2.096200e+02 +7 6184 -8.283997e+01 5.493700e+02 +9 6184 -7.526500e+02 4.859800e+02 +11 6184 -7.997998e+01 4.082900e+02 +7 6185 -4.540300e+02 5.539199e+02 +9 6185 -1.357990e+03 5.224700e+02 +10 6185 -9.258600e+02 -1.818500e+02 +11 6185 -6.569100e+02 4.404900e+02 +7 6186 1.357400e+02 5.572600e+02 +9 6186 -4.507500e+02 4.875000e+02 +7 6187 1.375230e+03 5.641899e+02 +9 6187 8.915801e+02 5.647700e+02 +7 6188 -4.106000e+02 5.836200e+02 +10 6188 -8.815400e+02 -1.560400e+02 +11 6188 -5.926700e+02 4.770500e+02 +18 6188 -1.070620e+03 2.464000e+02 +19 6188 1.261930e+03 5.329700e+02 +7 6189 1.103540e+03 5.880000e+02 +9 6189 6.604500e+02 5.461500e+02 +12 6189 -5.715002e+01 -2.585500e+02 +18 6189 1.428300e+02 2.067800e+02 +7 6190 4.684600e+02 6.011000e+02 +10 6190 1.885200e+02 -1.518400e+02 +7 6191 -3.804004e+01 6.027200e+02 +9 6191 -7.291700e+02 5.655801e+02 +7 6192 -7.459998e+01 6.061600e+02 +10 6192 -5.468000e+02 -1.428500e+02 +7 6193 -6.412000e+01 6.138700e+02 +9 6193 -7.602200e+02 5.798101e+02 +7 6194 -1.053199e+02 6.281700e+02 +9 6194 -8.088800e+02 5.964600e+02 +7 6195 -9.246997e+01 6.294800e+02 +9 6195 -7.930800e+02 5.983800e+02 +11 6195 -1.219100e+02 5.158600e+02 +7 6196 -1.255500e+02 6.306899e+02 +10 6196 -5.894000e+02 -1.197900e+02 +7 6197 -1.232200e+02 6.328700e+02 +11 6197 -1.560600e+02 5.191000e+02 +7 6198 -1.242200e+02 6.354100e+02 +11 6198 -1.574600e+02 5.223600e+02 +7 6199 -3.939500e+02 6.373201e+02 +9 6199 -1.281820e+03 6.370400e+02 +11 6199 -5.874100e+02 5.495000e+02 +19 6199 1.292120e+03 5.983000e+02 +7 6200 -3.995200e+02 6.373800e+02 +9 6200 -1.288780e+03 6.373301e+02 +11 6200 -5.938000e+02 5.500900e+02 +19 6200 1.284340e+03 5.985000e+02 +7 6201 -4.035600e+02 6.386100e+02 +9 6201 -1.293990e+03 6.383600e+02 +11 6201 -5.988800e+02 5.509399e+02 +19 6201 1.278500e+03 5.993500e+02 +7 6202 -8.296997e+01 6.403600e+02 +10 6202 -5.522200e+02 -1.105601e+02 +16 6202 1.857000e+02 5.672400e+02 +18 6202 -7.544100e+02 2.718900e+02 +20 6202 -6.432800e+02 3.501001e+01 +8 6203 2.718700e+02 3.400601e+02 +11 6203 4.480100e+02 3.570500e+02 +8 6204 2.575000e+02 3.725800e+02 +11 6204 4.378300e+02 3.805500e+02 +13 6204 -1.177320e+03 1.041000e+03 +8 6205 -8.468500e+02 6.131300e+02 +9 6205 -3.728600e+02 4.097900e+02 +8 6206 9.479700e+02 1.241000e+02 +9 6206 5.574700e+02 1.525100e+02 +8 6207 4.552700e+02 2.714700e+02 +11 6207 3.761100e+02 3.855900e+02 +9 6208 -9.602500e+02 4.225000e+02 +10 6208 -6.805400e+02 -2.412300e+02 +11 6208 -2.777000e+02 3.458300e+02 +18 6208 -8.680400e+02 1.548401e+02 +9 6209 1.224180e+03 2.847100e+02 +10 6209 8.367100e+02 -3.454500e+02 +18 6209 4.805300e+02 3.828003e+01 +9 6210 -1.240760e+03 3.088800e+02 +10 6210 -8.631900e+02 -3.244600e+02 +11 6210 -5.430300e+02 2.386400e+02 +14 6210 2.098200e+02 2.526000e+02 +16 6210 -2.945001e+01 3.770200e+02 +19 6210 1.281040e+03 3.010200e+02 +20 6210 -8.989300e+02 -1.234800e+02 +9 6211 -8.037700e+02 4.509199e+02 +11 6211 -1.239800e+02 3.841799e+02 +9 6212 -1.403180e+03 4.564299e+02 +10 6212 -9.610600e+02 -2.289301e+02 +11 6212 -6.990400e+02 3.767700e+02 +14 6212 1.578100e+02 3.066600e+02 +16 6212 -9.332001e+01 4.489500e+02 +19 6212 1.164940e+03 4.193201e+02 +20 6212 -9.843700e+02 -4.098999e+01 +9 6213 8.737500e+02 7.039001e+01 +10 6213 6.089800e+02 -4.885300e+02 +12 6213 7.431995e+01 -6.258800e+02 +18 6213 2.645300e+02 -8.879004e+01 +20 6213 2.339301e+02 -2.695000e+02 +9 6214 8.721201e+02 1.176300e+02 +10 6214 6.075300e+02 -4.563700e+02 +12 6214 7.393005e+01 -5.928600e+02 +18 6214 2.641200e+02 -5.994995e+01 +20 6214 2.338101e+02 -2.455100e+02 +9 6215 1.201890e+03 1.992000e+02 +10 6215 8.250200e+02 -4.038101e+02 +18 6215 4.666700e+02 -1.291003e+01 +9 6216 1.113290e+03 2.663000e+02 +10 6216 7.624199e+02 -3.654399e+02 +18 6216 4.174000e+02 2.833997e+01 +9 6217 1.150930e+03 3.270100e+02 +10 6217 7.741299e+02 -3.242300e+02 +18 6217 4.372600e+02 6.954004e+01 +9 6218 -1.193440e+03 3.989800e+02 +10 6218 -8.295000e+02 -2.618600e+02 +11 6218 -4.981200e+02 3.220800e+02 +14 6218 2.288100e+02 2.915500e+02 +18 6218 -1.013720e+03 1.444299e+02 +20 6218 -8.707300e+02 -7.477002e+01 +9 6219 3.471000e+02 -8.719971e+00 +10 6219 2.092000e+02 -4.807300e+02 +9 6220 8.960100e+02 7.800000e+01 +10 6220 6.244600e+02 -4.816700e+02 +12 6220 9.139001e+01 -6.188000e+02 +18 6220 2.778900e+02 -8.325000e+01 +9 6221 8.951201e+02 1.698401e+02 +10 6221 6.216001e+02 -4.175300e+02 +12 6221 9.078003e+01 -5.495601e+02 +18 6221 2.789700e+02 -2.900000e+01 +9 6222 1.020780e+03 1.839000e+02 +10 6222 7.048401e+02 -4.277700e+02 +18 6222 3.566600e+02 -1.978003e+01 +20 6222 3.119100e+02 -2.096500e+02 +9 6223 1.203670e+03 2.302600e+02 +10 6223 8.243701e+02 -3.833900e+02 +18 6223 4.676801e+02 5.349976e+00 +20 6223 4.058300e+02 -1.869000e+02 +9 6224 1.213080e+03 2.552400e+02 +10 6224 8.305901e+02 -3.656801e+02 +18 6224 4.740100e+02 2.082996e+01 +9 6225 1.221940e+03 3.016200e+02 +10 6225 8.347400e+02 -3.335100e+02 +18 6225 4.798600e+02 5.043994e+01 +9 6226 -9.413400e+02 4.075000e+02 +10 6226 -6.671100e+02 -2.515800e+02 +11 6226 -2.592900e+02 3.319200e+02 +18 6226 -8.562100e+02 1.445100e+02 +9 6227 -9.169500e+02 4.210701e+02 +10 6227 -6.516400e+02 -2.408000e+02 +20 6227 -7.205700e+02 -6.668005e+01 +9 6228 8.030000e+02 3.779004e+01 +10 6228 5.593999e+02 -5.110300e+02 +18 6228 2.211000e+02 -1.069301e+02 +9 6229 7.669900e+02 6.385999e+01 +10 6229 5.317500e+02 -4.802200e+02 +9 6230 -2.089100e+02 8.817004e+01 +10 6230 -1.559800e+02 -4.832000e+02 +11 6230 4.291700e+02 3.063000e+01 +12 6230 -7.653800e+02 -5.989900e+02 +9 6231 1.237720e+03 2.082000e+02 +10 6231 8.463401e+02 -3.976000e+02 +9 6232 -4.244900e+02 2.279000e+02 +10 6232 -3.200699e+02 -3.735200e+02 +12 6232 -9.554700e+02 -4.869000e+02 +9 6233 1.184440e+03 2.507400e+02 +10 6233 8.104399e+02 -3.699301e+02 +9 6234 -1.226830e+03 2.995200e+02 +10 6234 -8.523900e+02 -3.298000e+02 +11 6234 -5.298500e+02 2.296500e+02 +18 6234 -1.034660e+03 8.288000e+01 +9 6235 6.496599e+02 3.411500e+02 +10 6235 4.455601e+02 -2.966300e+02 +13 6235 1.363010e+03 8.276700e+02 +9 6236 1.044500e+03 3.604800e+02 +10 6236 7.068201e+02 -3.101600e+02 +20 6236 3.269600e+02 -1.169200e+02 +9 6237 -4.282800e+02 4.789199e+02 +10 6237 -3.183900e+02 -1.975699e+02 +9 6238 -1.298630e+03 5.630300e+02 +10 6238 -8.877300e+02 -1.546300e+02 +19 6238 1.253700e+03 5.318500e+02 +20 6238 -9.227700e+02 1.494000e+01 +9 6239 -5.094700e+02 -3.879900e+02 +11 6239 3.001700e+02 -4.214399e+02 +9 6240 -1.100100e+02 9.187000e+01 +10 6240 -7.131006e+01 -4.945100e+02 +18 6240 -3.360100e+02 -6.245996e+01 +20 6240 -2.839200e+02 -2.508700e+02 +9 6241 -9.717004e+01 1.895000e+02 +10 6241 -6.113000e+01 -4.290500e+02 +11 6241 5.214200e+02 1.265500e+02 +12 6241 -6.331200e+02 -5.218199e+02 +13 6241 -9.731400e+02 2.726699e+02 +18 6241 -3.250200e+02 -1.479980e+00 +20 6241 -2.750200e+02 -1.986300e+02 +9 6242 7.932500e+02 2.214600e+02 +10 6242 5.484099e+02 -3.815100e+02 +18 6242 2.160000e+02 5.839966e+00 +9 6243 1.162260e+03 2.519000e+02 +10 6243 7.960500e+02 -3.694100e+02 +9 6244 8.650400e+02 2.575300e+02 +10 6244 5.969399e+02 -3.557300e+02 +12 6244 6.621997e+01 -4.815500e+02 +9 6245 8.650400e+02 2.575300e+02 +10 6245 5.969399e+02 -3.557300e+02 +9 6246 1.215820e+03 2.726200e+02 +10 6246 8.313799e+02 -3.532500e+02 +18 6246 4.754100e+02 3.162000e+01 +9 6247 1.064090e+03 2.832100e+02 +10 6247 7.216599e+02 -3.629000e+02 +18 6247 3.885900e+02 4.091003e+01 +20 6247 3.367300e+02 -1.582800e+02 +9 6248 1.188130e+03 2.920000e+02 +10 6248 8.120300e+02 -3.411100e+02 +18 6248 4.597900e+02 4.414001e+01 +20 6248 3.977900e+02 -1.542200e+02 +9 6249 -1.460150e+03 2.976699e+02 +10 6249 -9.992200e+02 -3.329200e+02 +11 6249 -7.520600e+02 2.294800e+02 +14 6249 1.368000e+02 2.432800e+02 +16 6249 -1.130800e+02 3.665800e+02 +20 6249 -1.018960e+03 -1.257700e+02 +9 6250 -1.419240e+03 3.013101e+02 +10 6250 -9.744700e+02 -3.300699e+02 +11 6250 -7.132800e+02 2.308300e+02 +20 6250 -9.967400e+02 -1.246600e+02 +9 6251 1.202180e+03 3.051799e+02 +10 6251 8.212200e+02 -3.319200e+02 +18 6251 4.681400e+02 5.158008e+01 +20 6251 4.051100e+02 -1.478400e+02 +9 6252 -1.144880e+03 3.106599e+02 +11 6252 -3.800300e+02 2.451300e+02 +9 6253 -1.144880e+03 3.106599e+02 +11 6253 -3.800300e+02 2.451300e+02 +9 6254 1.167820e+03 3.479199e+02 +10 6254 7.924600e+02 -3.094900e+02 +9 6255 -4.427500e+02 3.904399e+02 +10 6255 -3.313600e+02 -2.585500e+02 +11 6255 2.135000e+02 3.206400e+02 +9 6256 -9.169100e+02 4.530801e+02 +10 6256 -6.517800e+02 -2.198500e+02 +11 6256 -2.369600e+02 3.763101e+02 +9 6257 -1.419740e+03 4.840200e+02 +10 6257 -9.684600e+02 -2.070699e+02 +14 6257 1.531200e+02 3.176300e+02 +20 6257 -9.918200e+02 -2.602002e+01 +9 6258 -1.470630e+03 5.507300e+02 +10 6258 -9.963800e+02 -1.620800e+02 +9 6259 -7.282700e+02 5.544800e+02 +10 6259 -5.150200e+02 -1.526600e+02 +11 6259 -6.260999e+01 4.743800e+02 +12 6259 -1.166130e+03 -2.237500e+02 +18 6259 -7.210200e+02 2.345300e+02 +9 6260 -3.186400e+02 -4.334998e+01 +10 6260 -2.414301e+02 -5.724000e+02 +12 6260 -8.735000e+02 -7.061000e+02 +9 6261 7.845801e+02 6.872998e+01 +10 6261 5.465801e+02 -4.905300e+02 +9 6262 -2.982500e+02 2.072600e+02 +10 6262 -2.234301e+02 -3.933199e+02 +9 6263 -2.982500e+02 2.072600e+02 +10 6263 -2.234301e+02 -3.933199e+02 +9 6264 6.130300e+02 2.571500e+02 +10 6264 4.222000e+02 -3.563000e+02 +13 6264 1.246360e+03 5.661000e+02 +17 6264 -7.181801e+02 5.287200e+02 +9 6265 1.243490e+03 3.012400e+02 +10 6265 8.493401e+02 -3.332100e+02 +18 6265 4.924900e+02 4.898999e+01 +20 6265 4.259600e+02 -1.496600e+02 +9 6266 1.243490e+03 3.012400e+02 +10 6266 8.493401e+02 -3.332100e+02 +18 6266 4.924900e+02 4.898999e+01 +20 6266 4.259600e+02 -1.496600e+02 +9 6267 -2.994900e+02 3.096100e+02 +10 6267 -2.248800e+02 -3.209100e+02 +11 6267 3.503199e+02 2.433800e+02 +9 6268 1.046160e+03 3.194099e+02 +10 6268 7.085200e+02 -3.376899e+02 +18 6268 3.781801e+02 6.225000e+01 +20 6268 3.275500e+02 -1.385000e+02 +9 6269 1.213030e+03 3.339000e+02 +10 6269 8.229099e+02 -3.175900e+02 +18 6269 4.759900e+02 6.746997e+01 +20 6269 4.113000e+02 -1.328800e+02 +9 6270 1.213030e+03 3.339000e+02 +10 6270 8.229099e+02 -3.175900e+02 +20 6270 4.113000e+02 -1.328800e+02 +9 6271 1.201440e+03 3.374800e+02 +10 6271 8.137400e+02 -3.159301e+02 +18 6271 4.708101e+02 7.210999e+01 +20 6271 4.059100e+02 -1.305200e+02 +9 6272 1.247650e+03 3.494299e+02 +10 6272 8.444900e+02 -3.072600e+02 +18 6272 4.977800e+02 7.747998e+01 +20 6272 4.299200e+02 -1.252200e+02 +9 6273 -1.159400e+03 3.977800e+02 +10 6273 -8.076600e+02 -2.618800e+02 +11 6273 -4.662400e+02 3.215200e+02 +18 6273 -9.926700e+02 1.427800e+02 +19 6273 1.347140e+03 4.010000e+02 +20 6273 -8.524600e+02 -7.543005e+01 +9 6274 -1.390130e+03 4.456100e+02 +10 6274 -9.541400e+02 -2.326300e+02 +11 6274 -6.853100e+02 3.677300e+02 +16 6274 -8.931000e+01 4.462300e+02 +9 6275 1.042960e+03 4.534700e+02 +10 6275 7.030701e+02 -2.483800e+02 +12 6275 2.538300e+02 -3.338800e+02 +18 6275 3.778800e+02 1.437100e+02 +9 6276 -1.144900e+03 5.246100e+02 +10 6276 -7.871500e+02 -1.785601e+02 +18 6276 -9.787100e+02 2.232700e+02 +20 6276 -8.401100e+02 -7.070007e+00 +9 6277 -5.124100e+02 -3.772700e+02 +11 6277 2.966600e+02 -4.118500e+02 +9 6278 -4.194800e+02 1.027800e+02 +10 6278 -3.161000e+02 -4.645900e+02 +9 6279 1.187550e+03 2.247900e+02 +10 6279 8.132800e+02 -3.862300e+02 +18 6279 4.588101e+02 1.859985e+00 +9 6280 8.445601e+02 2.355500e+02 +10 6280 5.847500e+02 -3.714900e+02 +18 6280 2.485500e+02 1.400000e+01 +9 6281 3.602900e+02 2.570100e+02 +10 6281 2.150200e+02 -2.554399e+02 +18 6281 -7.675000e+01 3.564001e+01 +9 6282 3.602900e+02 2.570100e+02 +10 6282 2.150200e+02 -2.554399e+02 +9 6283 3.304399e+02 2.564500e+02 +10 6283 1.903101e+02 -2.564000e+02 +18 6283 -9.548999e+01 3.572998e+01 +9 6284 1.013670e+03 3.002100e+02 +10 6284 6.876799e+02 -3.508600e+02 +18 6284 3.582500e+02 5.123999e+01 +9 6285 -2.673000e+02 3.200100e+02 +10 6285 -1.972100e+02 -3.162600e+02 +9 6286 1.222920e+03 3.499099e+02 +10 6286 8.286899e+02 -3.073600e+02 +9 6287 -1.246200e+02 3.524800e+02 +10 6287 -7.443005e+01 -3.260601e+02 +9 6288 -1.506360e+03 3.893600e+02 +10 6288 -1.025580e+03 -2.719399e+02 +11 6288 -7.971700e+02 3.152600e+02 +9 6289 -1.506360e+03 3.893600e+02 +10 6289 -1.025580e+03 -2.719399e+02 +11 6289 -7.971700e+02 3.152600e+02 +9 6290 -1.470110e+03 3.919800e+02 +10 6290 -1.003210e+03 -2.697700e+02 +11 6290 -7.625600e+02 3.176900e+02 +14 6290 1.348100e+02 2.793700e+02 +18 6290 -1.187530e+03 1.450701e+02 +20 6290 -1.022130e+03 -7.516003e+01 +9 6291 -1.446550e+03 3.941400e+02 +10 6291 -9.886600e+02 -2.680000e+02 +11 6291 -7.393500e+02 3.194800e+02 +16 6291 -1.095000e+02 4.182600e+02 +19 6291 1.134220e+03 3.588500e+02 +9 6292 -1.130110e+03 4.064299e+02 +10 6292 -7.886600e+02 -2.554000e+02 +11 6292 -4.396700e+02 3.314900e+02 +16 6292 1.695996e+01 4.360900e+02 +19 6292 1.369980e+03 4.157500e+02 +20 6292 -8.367800e+02 -7.181006e+01 +9 6293 6.866899e+02 4.579500e+02 +10 6293 4.687800e+02 -2.349600e+02 +12 6293 -3.659998e+01 -3.256801e+02 +9 6294 -1.428950e+03 4.759800e+02 +10 6294 -9.745200e+02 -2.122800e+02 +11 6294 -7.236000e+02 3.966200e+02 +9 6295 -7.808600e+02 5.559199e+02 +10 6295 -5.541500e+02 -1.508800e+02 +11 6295 -1.112800e+02 4.751700e+02 +20 6295 -6.442600e+02 4.159973e+00 +9 6296 -3.359900e+02 -1.452002e+01 +10 6296 -2.552900e+02 -5.505900e+02 +11 6296 3.140200e+02 -6.850000e+01 +9 6297 -3.135200e+02 -3.002930e-02 +10 6297 -2.391899e+02 -5.408700e+02 +11 6297 3.344800e+02 -5.478003e+01 +12 6297 -8.691300e+02 -6.705000e+02 +9 6298 9.862100e+02 2.971997e+01 +10 6298 6.853000e+02 -5.219500e+02 +12 6298 1.741000e+02 -6.589800e+02 +9 6299 7.909700e+02 4.054004e+01 +10 6299 5.520000e+02 -5.095500e+02 +12 6299 7.209961e+00 -6.493300e+02 +18 6299 2.132400e+02 -1.052700e+02 +20 6299 1.902900e+02 -2.849000e+02 +9 6300 7.909700e+02 4.054004e+01 +10 6300 5.520000e+02 -5.095500e+02 +20 6300 1.902900e+02 -2.849000e+02 +9 6301 6.054700e+02 1.069800e+02 +10 6301 4.200500e+02 -4.635900e+02 +9 6302 -1.530200e+02 1.718401e+02 +10 6302 -1.103000e+02 -4.317700e+02 +13 6302 -1.177650e+03 2.825400e+02 +18 6302 -3.640900e+02 -1.219995e+01 +9 6303 -1.190000e+02 1.927400e+02 +10 6303 -7.827002e+01 -4.264100e+02 +11 6303 5.032500e+02 1.307300e+02 +13 6303 -1.046790e+03 2.913301e+02 +18 6303 -3.397200e+02 6.700439e-01 +20 6303 -2.874399e+02 -1.970800e+02 +9 6304 -1.966899e+02 1.935100e+02 +10 6304 -1.446700e+02 -4.097200e+02 +13 6304 -1.338910e+03 3.929299e+02 +9 6305 1.146920e+03 2.037600e+02 +10 6305 7.847400e+02 -4.045200e+02 +20 6305 3.774600e+02 -1.997300e+02 +9 6306 1.169150e+03 2.048301e+02 +10 6306 8.008201e+02 -4.016200e+02 +18 6306 4.478400e+02 -8.709961e+00 +20 6306 3.886100e+02 -1.993600e+02 +9 6307 1.157790e+03 2.048700e+02 +10 6307 7.925901e+02 -4.029600e+02 +18 6307 4.412700e+02 -8.930054e+00 +20 6307 3.828101e+02 -1.994800e+02 +9 6308 -4.022000e+02 2.200500e+02 +10 6308 -3.027400e+02 -3.798500e+02 +12 6308 -9.360700e+02 -4.924100e+02 +18 6308 -5.253000e+02 2.215002e+01 +20 6308 -4.461100e+02 -1.795000e+02 +9 6309 1.054580e+03 2.894199e+02 +10 6309 7.146499e+02 -3.577700e+02 +18 6309 3.826200e+02 4.393005e+01 +9 6310 1.030920e+03 3.012300e+02 +10 6310 6.988999e+02 -3.500601e+02 +18 6310 3.690900e+02 5.143994e+01 +20 6310 3.197500e+02 -1.483600e+02 +9 6311 1.234660e+03 3.100801e+02 +10 6311 8.422800e+02 -3.276801e+02 +18 6311 4.870100e+02 5.421997e+01 +9 6312 1.016800e+03 3.663500e+02 +10 6312 6.876101e+02 -3.070601e+02 +12 6312 2.331700e+02 -3.999900e+02 +18 6312 3.606200e+02 9.121997e+01 +9 6313 1.058320e+03 3.700601e+02 +10 6313 7.151799e+02 -3.038199e+02 +12 6313 2.643900e+02 -3.972900e+02 +18 6313 3.861899e+02 9.352002e+01 +20 6313 3.337300e+02 -1.126801e+02 +9 6314 1.030440e+03 3.704600e+02 +10 6314 6.966899e+02 -3.044100e+02 +20 6314 3.192400e+02 -1.124301e+02 +9 6315 1.007010e+03 3.760901e+02 +10 6315 6.827500e+02 -2.998500e+02 +12 6315 2.277400e+02 -3.917700e+02 +18 6315 3.566500e+02 9.778003e+01 +20 6315 3.072700e+02 -1.091100e+02 +9 6316 1.033160e+03 3.772000e+02 +10 6316 6.975801e+02 -2.990900e+02 +18 6316 3.708101e+02 9.763000e+01 +20 6316 3.207200e+02 -1.088500e+02 +9 6317 1.062510e+03 3.791899e+02 +10 6317 7.174600e+02 -2.977000e+02 +12 6317 2.672900e+02 -3.903500e+02 +18 6317 3.887800e+02 9.843994e+01 +20 6317 3.356801e+02 -1.080000e+02 +9 6318 1.062510e+03 3.791899e+02 +10 6318 7.174600e+02 -2.977000e+02 +12 6318 2.672900e+02 -3.903500e+02 +18 6318 3.887800e+02 9.843994e+01 +20 6318 3.356801e+02 -1.080000e+02 +9 6319 1.006250e+03 3.907100e+02 +10 6319 6.832100e+02 -2.899700e+02 +20 6319 3.070800e+02 -1.016400e+02 +9 6320 1.044860e+03 3.916500e+02 +10 6320 7.061201e+02 -2.891500e+02 +12 6320 2.544800e+02 -3.806000e+02 +18 6320 3.781700e+02 1.062300e+02 +20 6320 3.263700e+02 -1.015601e+02 +9 6321 1.035850e+03 4.121599e+02 +10 6321 6.990901e+02 -2.762000e+02 +12 6321 2.476899e+02 -3.654200e+02 +18 6321 3.729200e+02 1.187400e+02 +9 6322 6.194800e+02 4.148700e+02 +10 6322 4.233701e+02 -2.648300e+02 +13 6322 1.252560e+03 9.616399e+02 +20 6322 1.048600e+02 -8.556006e+01 +9 6323 6.084099e+02 4.147400e+02 +10 6323 4.161001e+02 -2.651000e+02 +12 6323 -9.837000e+01 -3.587300e+02 +13 6323 1.219790e+03 9.614399e+02 +20 6323 9.914001e+01 -8.541003e+01 +9 6324 6.186699e+02 4.491699e+02 +10 6324 4.220901e+02 -2.408300e+02 +13 6324 1.251140e+03 1.066970e+03 +17 6324 -8.755100e+02 8.436100e+02 +20 6324 1.045500e+02 -6.725000e+01 +9 6325 1.014630e+03 4.602400e+02 +10 6325 6.838701e+02 -2.447200e+02 +12 6325 2.325800e+02 -3.285800e+02 +18 6325 3.606100e+02 1.480400e+02 +9 6326 6.184099e+02 4.600100e+02 +10 6326 4.218999e+02 -2.334800e+02 +20 6326 1.045300e+02 -6.195996e+01 +9 6327 7.320400e+02 4.719299e+02 +10 6327 4.986599e+02 -2.248300e+02 +9 6328 -1.134550e+03 5.033700e+02 +10 6328 -7.808500e+02 -1.939700e+02 +11 6328 -4.461200e+02 4.219600e+02 +12 6328 -1.482750e+03 -2.555400e+02 +18 6328 -9.736000e+02 2.081400e+02 +20 6328 -8.348500e+02 -1.971997e+01 +9 6329 -7.368100e+02 5.651400e+02 +10 6329 -5.209301e+02 -1.467600e+02 +11 6329 -7.107001e+01 4.831700e+02 +12 6329 -1.172250e+03 -2.159900e+02 +16 6329 2.170400e+02 5.393400e+02 +18 6329 -7.259200e+02 2.405901e+02 +20 6329 -6.189000e+02 8.549988e+00 +9 6330 -2.773000e+02 5.717004e+01 +10 6330 -2.092200e+02 -5.125699e+02 +20 6330 -3.796200e+02 -2.685300e+02 +9 6331 1.212320e+03 1.183101e+02 +10 6331 8.338401e+02 -4.599600e+02 +9 6332 1.135930e+03 1.596599e+02 +10 6332 7.779800e+02 -4.366899e+02 +9 6333 7.005500e+02 1.641000e+02 +10 6333 4.853601e+02 -4.235100e+02 +20 6333 1.436700e+02 -2.183000e+02 +9 6334 1.135390e+03 2.024800e+02 +10 6334 7.765400e+02 -4.065500e+02 +18 6334 4.284100e+02 -1.015002e+01 +20 6334 3.719399e+02 -2.002000e+02 +9 6335 1.114750e+03 2.064600e+02 +10 6335 7.614900e+02 -4.069399e+02 +18 6335 4.163000e+02 -1.027002e+01 +20 6335 3.666300e+02 -1.994399e+02 +9 6336 1.114750e+03 2.064600e+02 +10 6336 7.614900e+02 -4.069399e+02 +18 6336 4.163000e+02 -1.027002e+01 +9 6337 1.119910e+03 2.071400e+02 +10 6337 7.651201e+02 -4.057700e+02 +9 6338 1.119910e+03 2.071400e+02 +10 6338 7.651201e+02 -4.057700e+02 +9 6339 1.104130e+03 2.130901e+02 +10 6339 7.536299e+02 -4.016300e+02 +9 6340 1.104130e+03 2.130901e+02 +10 6340 7.536299e+02 -4.016300e+02 +9 6341 1.114380e+03 2.153500e+02 +10 6341 7.607500e+02 -3.989900e+02 +9 6342 1.114380e+03 2.153500e+02 +10 6342 7.607500e+02 -3.989900e+02 +9 6343 1.178970e+03 2.187800e+02 +10 6343 8.081799e+02 -3.915800e+02 +18 6343 4.539700e+02 1.500244e-01 +20 6343 3.936500e+02 -1.920900e+02 +9 6344 1.104020e+03 2.214500e+02 +10 6344 7.533701e+02 -3.967300e+02 +9 6345 1.057010e+03 2.370701e+02 +10 6345 7.173999e+02 -3.922500e+02 +20 6345 3.329900e+02 -1.818300e+02 +9 6346 -1.419700e+02 2.448000e+02 +10 6346 -9.905005e+01 -3.864700e+02 +11 6346 4.852900e+02 1.781900e+02 +13 6346 -1.132570e+03 4.852800e+02 +18 6346 -3.553300e+02 3.196997e+01 +20 6346 -3.003300e+02 -1.693400e+02 +9 6347 6.961299e+02 2.503500e+02 +10 6347 4.810601e+02 -3.610200e+02 +9 6348 -1.980699e+02 2.497300e+02 +10 6348 -1.464200e+02 -3.728700e+02 +18 6348 -3.932600e+02 3.652002e+01 +20 6348 -3.327200e+02 -1.668700e+02 +9 6349 7.430400e+02 2.508500e+02 +10 6349 5.127300e+02 -3.611000e+02 +17 6349 -4.933800e+02 5.055701e+02 +18 6349 1.860500e+02 2.506995e+01 +20 6349 1.654399e+02 -1.725400e+02 +9 6350 3.229200e+02 2.599600e+02 +10 6350 1.841300e+02 -2.531600e+02 +9 6351 3.229200e+02 2.599600e+02 +10 6351 1.841300e+02 -2.531600e+02 +9 6352 -2.352200e+02 2.739099e+02 +10 6352 -1.749700e+02 -3.514100e+02 +13 6352 -1.469550e+03 6.668000e+02 +9 6353 1.046520e+03 2.785000e+02 +10 6353 7.099299e+02 -3.652100e+02 +18 6353 3.782300e+02 3.719995e+01 +20 6353 3.281801e+02 -1.603300e+02 +9 6354 1.046520e+03 2.785000e+02 +10 6354 7.099299e+02 -3.652100e+02 +18 6354 3.782300e+02 3.719995e+01 +20 6354 3.281801e+02 -1.603300e+02 +9 6355 -1.470120e+03 2.841300e+02 +10 6355 -1.005590e+03 -3.428600e+02 +11 6355 -7.612300e+02 2.166000e+02 +9 6356 1.045620e+03 2.891500e+02 +10 6356 7.095901e+02 -3.578400e+02 +9 6357 1.045620e+03 2.891500e+02 +10 6357 7.095901e+02 -3.578400e+02 +18 6357 3.776700e+02 4.390002e+01 +9 6358 1.014490e+03 2.886100e+02 +10 6358 6.888101e+02 -3.588101e+02 +9 6359 6.995100e+02 2.916500e+02 +10 6359 4.821299e+02 -3.334399e+02 +13 6359 1.520020e+03 6.600500e+02 +18 6359 1.607000e+02 5.071997e+01 +20 6359 1.435400e+02 -1.507400e+02 +9 6360 1.211440e+03 3.044900e+02 +10 6360 8.278999e+02 -3.325601e+02 +18 6360 4.737100e+02 5.065002e+01 +9 6361 -1.128090e+03 3.069000e+02 +10 6361 -7.903700e+02 -3.227100e+02 +11 6361 -4.362900e+02 2.374800e+02 +20 6361 -8.373400e+02 -1.253500e+02 +9 6362 1.063550e+03 3.332300e+02 +10 6362 7.199399e+02 -3.283900e+02 +18 6362 3.892100e+02 7.037000e+01 +9 6363 1.080700e+03 3.987400e+02 +10 6363 7.278601e+02 -2.844500e+02 +18 6363 3.989800e+02 1.099600e+02 +9 6364 -2.924100e+02 4.070801e+02 +10 6364 -2.191100e+02 -2.522500e+02 +9 6365 1.016240e+03 4.101400e+02 +10 6365 6.865200e+02 -2.779800e+02 +12 6365 2.331400e+02 -3.663800e+02 +18 6365 3.613800e+02 1.176899e+02 +20 6365 3.123800e+02 -9.158997e+01 +9 6366 1.030090e+03 4.154399e+02 +10 6366 6.951799e+02 -2.743600e+02 +9 6367 1.008590e+03 4.180601e+02 +10 6367 6.801899e+02 -2.728700e+02 +18 6367 3.566801e+02 1.231000e+02 +9 6368 7.083401e+02 4.480901e+02 +10 6368 4.829800e+02 -2.412200e+02 +12 6368 -2.266003e+01 -3.338900e+02 +13 6368 1.525140e+03 1.057780e+03 +17 6368 -7.144100e+02 8.314000e+02 +18 6368 1.713900e+02 1.460100e+02 +9 6369 6.649800e+02 4.484500e+02 +10 6369 4.535701e+02 -2.409500e+02 +17 6369 -7.914600e+02 8.373600e+02 +18 6369 1.454301e+02 1.475500e+02 +20 6369 1.288199e+02 -6.789001e+01 +9 6370 -3.532200e+02 -4.384998e+01 +10 6370 -2.681200e+02 -5.714200e+02 +9 6371 -3.477500e+02 -3.971997e+01 +10 6371 -2.643400e+02 -5.683800e+02 +9 6372 -3.539900e+02 -4.006995e+01 +10 6372 -2.694200e+02 -5.683600e+02 +9 6373 8.677200e+02 8.743994e+01 +10 6373 6.040601e+02 -4.759600e+02 +9 6374 8.802500e+02 8.784998e+01 +10 6374 6.132400e+02 -4.756899e+02 +9 6375 -1.065100e+02 2.017700e+02 +10 6375 -6.664001e+01 -4.202700e+02 +11 6375 5.123800e+02 1.383600e+02 +12 6375 -6.386000e+02 -5.124301e+02 +13 6375 -9.971900e+02 3.129299e+02 +18 6375 -3.301400e+02 6.329956e+00 +9 6376 -1.065100e+02 2.017700e+02 +10 6376 -6.664001e+01 -4.202700e+02 +11 6376 5.123800e+02 1.383600e+02 +13 6376 -9.971900e+02 3.129299e+02 +18 6376 -3.301400e+02 6.329956e+00 +9 6377 6.269600e+02 2.090901e+02 +10 6377 4.312000e+02 -3.919500e+02 +12 6377 -1.192800e+02 -5.179900e+02 +17 6377 -6.940100e+02 4.332300e+02 +9 6378 1.099020e+03 2.323900e+02 +10 6378 7.494199e+02 -3.907600e+02 +18 6378 4.075800e+02 7.349976e+00 +9 6379 1.109870e+03 2.337800e+02 +10 6379 7.567400e+02 -3.889700e+02 +18 6379 4.135699e+02 8.760010e+00 +20 6379 3.587000e+02 -1.849500e+02 +9 6380 -1.367200e+02 2.450901e+02 +10 6380 -9.390002e+01 -3.855900e+02 +12 6380 -6.781800e+02 -4.791100e+02 +13 6380 -1.111410e+03 4.839900e+02 +18 6380 -3.514700e+02 3.280005e+01 +20 6380 -2.973101e+02 -1.692400e+02 +9 6381 -1.367200e+02 2.450901e+02 +10 6381 -9.390002e+01 -3.855900e+02 +12 6381 -6.781800e+02 -4.791100e+02 +18 6381 -3.514700e+02 3.280005e+01 +20 6381 -2.973101e+02 -1.692400e+02 +9 6382 -2.663400e+02 2.963600e+02 +10 6382 -1.988900e+02 -3.321300e+02 +9 6383 1.174570e+03 2.967500e+02 +10 6383 8.017900e+02 -3.396200e+02 +18 6383 4.517600e+02 4.666003e+01 +9 6384 1.236810e+03 3.000400e+02 +10 6384 8.447100e+02 -3.342700e+02 +9 6385 1.214290e+03 3.113101e+02 +10 6385 8.293201e+02 -3.270200e+02 +9 6386 1.241630e+03 3.126200e+02 +10 6386 8.471899e+02 -3.256600e+02 +9 6387 1.059030e+03 3.344700e+02 +10 6387 7.164500e+02 -3.262400e+02 +18 6387 3.861100e+02 7.215991e+01 +9 6388 1.059030e+03 3.344700e+02 +10 6388 7.164500e+02 -3.262400e+02 +18 6388 3.861100e+02 7.215991e+01 +9 6389 5.612700e+02 3.473600e+02 +10 6389 3.841201e+02 -2.935400e+02 +9 6390 -2.234500e+02 4.052200e+02 +10 6390 -1.574800e+02 -2.698000e+02 +9 6391 -2.307600e+02 4.053401e+02 +10 6391 -1.625200e+02 -2.701500e+02 +9 6392 1.024820e+03 4.132000e+02 +10 6392 6.914900e+02 -2.756700e+02 +9 6393 1.002900e+03 4.227200e+02 +10 6393 6.770200e+02 -2.697600e+02 +12 6393 2.242000e+02 -3.566100e+02 +18 6393 3.536100e+02 1.259600e+02 +9 6394 6.811799e+02 4.513800e+02 +10 6394 4.647700e+02 -2.388199e+02 +12 6394 -4.229004e+01 -3.307900e+02 +13 6394 1.444360e+03 1.070880e+03 +9 6395 -4.843300e+02 4.689800e+02 +10 6395 -3.591400e+02 -2.031400e+02 +9 6396 -7.649600e+02 4.711699e+02 +10 6396 -5.511600e+02 -2.039700e+02 +12 6396 -1.212020e+03 -2.891200e+02 +20 6396 -6.378700e+02 -4.170996e+01 +9 6397 -5.562600e+02 4.825701e+02 +10 6397 -4.094600e+02 -1.933000e+02 +12 6397 -1.050470e+03 -2.840400e+02 +9 6398 -5.562600e+02 4.825701e+02 +10 6398 -4.094600e+02 -1.933000e+02 +9 6399 -1.178700e+03 4.872700e+02 +10 6399 -8.127600e+02 -2.040300e+02 +11 6399 -4.852600e+02 4.073600e+02 +9 6400 5.992800e+02 5.085500e+02 +10 6400 4.080500e+02 -2.005800e+02 +12 6400 -1.043600e+02 -2.859500e+02 +17 6400 -9.128400e+02 9.578601e+02 +9 6401 6.310701e+02 5.168101e+02 +10 6401 4.291899e+02 -1.951100e+02 +12 6401 -8.025000e+01 -2.801899e+02 +9 6402 -1.510340e+03 5.534000e+02 +10 6402 -1.020910e+03 -1.619600e+02 +11 6402 -8.030100e+02 4.714399e+02 +18 6402 -1.209740e+03 2.464099e+02 +9 6403 -8.385500e+02 6.268401e+02 +10 6403 -5.923600e+02 -1.014900e+02 +11 6403 -1.634600e+02 5.423600e+02 +9 6404 7.910500e+02 2.955005e+01 +10 6404 5.522000e+02 -5.160699e+02 +9 6405 7.698000e+02 5.116003e+01 +10 6405 5.367100e+02 -5.015000e+02 +9 6406 7.698000e+02 5.116003e+01 +10 6406 5.367100e+02 -5.015000e+02 +9 6407 -2.101300e+02 8.051001e+01 +10 6407 -1.561200e+02 -4.889800e+02 +9 6408 -2.718000e+02 1.051300e+02 +10 6408 -2.061100e+02 -4.684500e+02 +13 6408 -1.614030e+03 1.449000e+02 +18 6408 -4.447000e+02 -5.270996e+01 +9 6409 -4.722300e+02 1.213700e+02 +10 6409 -3.551300e+02 -4.496100e+02 +11 6409 1.854200e+02 6.242999e+01 +9 6410 8.459199e+02 1.299000e+02 +10 6410 5.874299e+02 -4.457900e+02 +12 6410 5.230005e+01 -5.797500e+02 +9 6411 9.793601e+02 1.768101e+02 +10 6411 6.759700e+02 -4.177800e+02 +9 6412 3.243000e+02 2.312900e+02 +10 6412 1.857300e+02 -2.774500e+02 +9 6413 1.141130e+03 2.374000e+02 +10 6413 7.793799e+02 -3.835000e+02 +18 6413 4.319301e+02 1.079004e+01 +20 6413 3.744800e+02 -1.829301e+02 +9 6414 1.173730e+03 2.415100e+02 +10 6414 8.031499e+02 -3.776000e+02 +18 6414 4.504600e+02 1.243994e+01 +9 6415 9.034800e+02 2.535701e+02 +10 6415 6.241499e+02 -3.577100e+02 +12 6415 9.634998e+01 -4.844600e+02 +9 6416 -1.726600e+02 2.550300e+02 +10 6416 -1.272700e+02 -3.718600e+02 +11 6416 4.605900e+02 1.883600e+02 +13 6416 -1.255300e+03 5.610901e+02 +18 6416 -3.771400e+02 3.914001e+01 +20 6416 -3.184700e+02 -1.633900e+02 +9 6417 -2.223500e+02 2.636200e+02 +10 6417 -1.651200e+02 -3.585601e+02 +11 6417 4.179000e+02 1.994900e+02 +12 6417 -7.723900e+02 -4.619900e+02 +9 6418 8.073201e+02 2.683301e+02 +10 6418 5.576799e+02 -3.487500e+02 +9 6419 6.955000e+02 2.759099e+02 +10 6419 4.794199e+02 -3.443700e+02 +9 6420 -3.491300e+02 2.935701e+02 +10 6420 -2.627700e+02 -3.291600e+02 +9 6421 9.003301e+02 3.455400e+02 +10 6421 6.176899e+02 -3.038400e+02 +12 6421 1.120601e+02 -4.146400e+02 +9 6422 5.958000e+02 4.052200e+02 +10 6422 4.070000e+02 -2.701200e+02 +12 6422 -1.091500e+02 -3.645200e+02 +18 6422 1.016000e+02 1.220701e+02 +20 6422 9.134998e+01 -8.965002e+01 +9 6423 -1.195110e+03 4.159399e+02 +10 6423 -8.297500e+02 -2.499700e+02 +11 6423 -4.993700e+02 3.395400e+02 +18 6423 -1.014680e+03 1.552200e+02 +19 6423 1.318130e+03 4.147100e+02 +9 6424 5.983501e+02 4.234800e+02 +10 6424 4.089199e+02 -2.590100e+02 +12 6424 -1.064600e+02 -3.510699e+02 +13 6424 1.188670e+03 9.910801e+02 +18 6424 1.043400e+02 1.320901e+02 +9 6425 6.130601e+02 4.652600e+02 +10 6425 4.179600e+02 -2.295800e+02 +9 6426 6.441399e+02 5.021400e+02 +10 6426 4.374299e+02 -2.052100e+02 +12 6426 -7.126001e+01 -2.920500e+02 +17 6426 -8.301100e+02 9.399299e+02 +20 6426 1.171600e+02 -4.098999e+01 +9 6427 -1.165360e+03 5.515000e+02 +10 6427 -8.000800e+02 -1.634900e+02 +11 6427 -4.750300e+02 4.682300e+02 +14 6427 2.487200e+02 3.480300e+02 +16 6427 1.819995e+01 5.102700e+02 +18 6427 -9.923000e+02 2.384199e+02 +19 6427 1.374500e+03 5.375500e+02 +20 6427 -8.503900e+02 5.469971e+00 +9 6428 -7.345300e+02 5.718301e+02 +10 6428 -5.183600e+02 -1.429301e+02 +11 6428 -6.741998e+01 4.898101e+02 +18 6428 -7.239300e+02 2.443500e+02 +9 6429 1.564301e+02 -6.442004e+01 +11 6429 8.194600e+02 -1.186100e+02 +9 6430 7.432200e+02 2.556006e+01 +10 6430 5.197200e+02 -5.195699e+02 +12 6430 -3.566003e+01 -6.604200e+02 +13 6430 1.656990e+03 -1.807000e+02 +18 6430 1.837000e+02 -1.135000e+02 +9 6431 7.500801e+02 1.313000e+02 +10 6431 5.209900e+02 -4.456300e+02 +9 6432 9.794600e+02 1.707800e+02 +10 6432 6.761599e+02 -4.226801e+02 +12 6432 1.681300e+02 -5.494500e+02 +9 6433 -3.014100e+02 2.160100e+02 +10 6433 -2.259301e+02 -3.851100e+02 +11 6433 3.466700e+02 1.539500e+02 +13 6433 -1.703070e+03 5.215701e+02 +18 6433 -4.605699e+02 1.905005e+01 +9 6434 7.974399e+02 2.925400e+02 +10 6434 5.493999e+02 -3.324399e+02 +18 6434 2.190300e+02 4.890002e+01 +9 6435 -4.124800e+02 3.872400e+02 +10 6435 -3.083700e+02 -2.615601e+02 +9 6436 7.656001e+02 4.403900e+02 +10 6436 5.216399e+02 -2.460601e+02 +12 6436 2.106006e+01 -3.404399e+02 +10 6437 -2.760500e+02 -3.526899e+02 +11 6437 2.866500e+02 1.958800e+02 +12 6437 -9.048700e+02 -4.646300e+02 +10 6438 -2.760500e+02 -3.526899e+02 +11 6438 2.866500e+02 1.958800e+02 +10 6439 -8.591500e+02 -1.990900e+02 +11 6439 -5.506300e+02 4.156700e+02 +14 6439 2.130300e+02 3.277700e+02 +16 6439 -2.846002e+01 4.794399e+02 +10 6440 -2.135200e+02 -5.719600e+02 +11 6440 3.659301e+02 -9.142999e+01 +12 6440 -8.395600e+02 -7.044000e+02 +18 6440 -4.527200e+02 -1.429100e+02 +20 6440 -3.835200e+02 -3.219399e+02 +10 6441 -1.296700e+02 -5.655601e+02 +11 6441 7.059200e+02 -1.726200e+02 +12 6441 -8.546300e+02 -7.735900e+02 +10 6442 -1.367500e+02 -4.371801e+02 +11 6442 4.488900e+02 9.807001e+01 +12 6442 -7.381800e+02 -5.453700e+02 +13 6442 -1.304810e+03 2.646899e+02 +10 6443 -1.872900e+02 -3.196500e+02 +11 6443 3.927700e+02 2.507400e+02 +12 6443 -7.971600e+02 -4.195400e+02 +13 6443 -1.519520e+03 8.121300e+02 +20 6443 -3.611400e+02 -1.290200e+02 +10 6444 -2.849000e+02 -2.892100e+02 +11 6444 2.749700e+02 2.797800e+02 +10 6445 -7.647300e+02 -2.433900e+02 +11 6445 -4.024200e+02 3.466799e+02 +12 6445 -1.463350e+03 -3.196000e+02 +18 6445 -9.508700e+02 1.578401e+02 +10 6446 -2.564800e+02 -2.073500e+02 +11 6446 3.085800e+02 3.965000e+02 +10 6447 -7.803300e+02 -1.874900e+02 +11 6447 -4.458100e+02 4.309000e+02 +12 6447 -1.480660e+03 -2.474301e+02 +14 6447 2.604100e+02 3.341800e+02 +16 6447 3.663000e+01 4.928400e+02 +19 6447 1.409200e+03 5.109299e+02 +20 6447 -8.345300e+02 -1.435999e+01 +10 6448 -2.520100e+02 -5.344500e+02 +11 6448 3.182000e+02 -4.542999e+01 +12 6448 -8.835600e+02 -6.640699e+02 +10 6449 -9.905005e+01 -3.864700e+02 +11 6449 4.852900e+02 1.781900e+02 +13 6449 -1.132570e+03 4.852800e+02 +20 6449 -3.003300e+02 -1.693400e+02 +10 6450 -9.767004e+01 -3.681000e+02 +11 6450 4.866600e+02 2.030400e+02 +13 6450 -1.126590e+03 5.642300e+02 +10 6451 -2.313800e+02 -5.498400e+02 +11 6451 3.432000e+02 -6.654999e+01 +10 6452 -2.397700e+02 -5.148500e+02 +11 6452 3.335000e+02 -1.991998e+01 +12 6452 -8.688800e+02 -6.414900e+02 +10 6453 -6.059998e+01 -4.362500e+02 +11 6453 5.217700e+02 1.172800e+02 +12 6453 -6.328800e+02 -5.305601e+02 +13 6453 -9.711600e+02 2.405701e+02 +18 6453 -3.249700e+02 -7.959961e+00 +20 6453 -2.749600e+02 -2.038300e+02 +10 6454 -1.107000e+02 -3.501000e+02 +11 6454 4.775100e+02 2.229100e+02 +13 6454 -1.179850e+03 6.534800e+02 +20 6454 -3.074800e+02 -1.453600e+02 +10 6455 -1.540000e+02 -3.374500e+02 +11 6455 4.312900e+02 2.310000e+02 +12 6455 -7.582600e+02 -4.373700e+02 +13 6455 -1.372250e+03 7.260701e+02 +10 6456 -1.577100e+02 -3.334800e+02 +11 6456 4.267900e+02 2.351400e+02 +13 6456 -1.388490e+03 7.437700e+02 +10 6457 -2.214700e+02 -2.031300e+02 +11 6457 3.532400e+02 4.048101e+02 +12 6457 -8.350900e+02 -2.938000e+02 +18 6457 -4.537700e+02 1.790601e+02 +20 6457 -3.838900e+02 -4.378003e+01 +10 6458 -6.014900e+02 -1.567900e+02 +11 6458 -1.704900e+02 4.626899e+02 +18 6458 -7.963500e+02 2.294800e+02 +10 6459 -6.449200e+02 -1.134500e+02 +11 6459 -2.397100e+02 5.265601e+02 +16 6459 1.130900e+02 5.596400e+02 +18 6459 -8.389100e+02 2.720300e+02 +20 6459 -7.169300e+02 3.501001e+01 +10 6460 -2.093199e+02 -5.358500e+02 +11 6460 3.684000e+02 -4.608002e+01 +20 6460 -3.800900e+02 -2.943800e+02 +10 6461 -1.583300e+02 -3.692600e+02 +11 6461 4.259200e+02 1.873700e+02 +20 6461 -3.412800e+02 -1.677000e+02 +10 6462 -5.781400e+02 -1.141700e+02 +11 6462 -1.438100e+02 5.245701e+02 +10 6463 -2.176700e+02 -5.499200e+02 +11 6463 3.591700e+02 -6.570001e+01 +10 6464 -3.245601e+02 -4.613500e+02 +11 6464 2.268400e+02 4.801001e+01 +10 6465 -2.484100e+02 -3.305900e+02 +11 6465 3.208900e+02 2.273500e+02 +12 6465 -8.724000e+02 -4.371400e+02 +10 6466 -2.627700e+02 -3.291600e+02 +11 6466 3.030900e+02 2.283200e+02 +10 6467 -2.382800e+02 -2.819800e+02 +11 6467 3.330500e+02 2.945800e+02 +10 6468 -8.998000e+02 -1.421300e+02 +11 6468 -6.258300e+02 4.986300e+02 +0 6469 -1.206530e+03 3.967000e+02 +14 6469 -1.257500e+02 3.341400e+02 +0 6470 -1.038640e+03 6.467200e+02 +19 6470 5.208800e+02 6.861600e+02 +0 6471 1.104440e+03 2.319199e+02 +16 6471 6.826801e+02 4.177300e+02 +0 6472 -1.376700e+03 5.091003e+01 +15 6472 5.987700e+02 7.044000e+01 +0 6473 1.525400e+03 1.483500e+02 +16 6473 9.438700e+02 3.316000e+02 +0 6474 1.120370e+03 1.488000e+02 +8 6474 2.705800e+02 1.430700e+02 +16 6474 6.919301e+02 3.647000e+02 +0 6475 1.078890e+03 1.993700e+02 +16 6475 6.666899e+02 3.972000e+02 +0 6476 -1.663190e+03 2.723800e+02 +19 6476 -1.767600e+02 2.816400e+02 +0 6477 -1.433720e+03 4.045300e+02 +15 6477 5.579900e+02 2.703000e+02 +16 6477 -6.416700e+02 4.245800e+02 +0 6478 -9.755700e+02 4.888000e+02 +16 6478 -4.772400e+02 4.940300e+02 +0 6479 -1.350020e+03 5.259099e+02 +4 6479 -1.268900e+02 4.666899e+02 +7 6479 -1.091330e+03 5.934600e+02 +10 6479 -1.474490e+03 -1.231801e+02 +15 6479 6.056200e+02 3.477400e+02 +16 6479 -5.967800e+02 4.964700e+02 +0 6480 -9.093800e+02 6.781200e+02 +15 6480 8.386300e+02 4.606400e+02 +16 6480 -3.802700e+02 6.002300e+02 +19 6480 6.285701e+02 7.272900e+02 +0 6481 -1.450300e+03 7.049299e+02 +4 6481 -1.831700e+02 5.584500e+02 +7 6481 -1.185750e+03 7.419100e+02 +10 6481 -1.555580e+03 2.046997e+01 +14 6481 -2.422900e+02 4.815200e+02 +15 6481 5.399900e+02 4.492400e+02 +16 6481 -6.654000e+02 5.995400e+02 +19 6481 1.390699e+02 7.145400e+02 +0 6482 -1.558850e+03 7.335400e+02 +4 6482 -2.385800e+02 5.724000e+02 +5 6482 -1.132220e+03 8.273900e+02 +7 6482 -1.281460e+03 7.709299e+02 +10 6482 -1.649860e+03 5.259998e+01 +14 6482 -2.939600e+02 4.963700e+02 +15 6482 4.764000e+02 4.650900e+02 +16 6482 -7.313800e+02 6.161500e+02 +19 6482 3.627002e+01 7.343000e+02 +0 6483 -1.558850e+03 7.335400e+02 +4 6483 -2.385800e+02 5.724000e+02 +5 6483 -1.132220e+03 8.273900e+02 +7 6483 -1.281460e+03 7.709299e+02 +10 6483 -1.649860e+03 5.259998e+01 +14 6483 -2.939600e+02 4.963700e+02 +15 6483 4.764000e+02 4.650900e+02 +16 6483 -7.313800e+02 6.161500e+02 +19 6483 3.627002e+01 7.343000e+02 +20 6483 -1.472310e+03 1.379099e+02 +0 6484 -1.278210e+03 7.639700e+02 +4 6484 -9.867004e+01 5.941100e+02 +7 6484 -1.048600e+03 7.858400e+02 +10 6484 -1.415480e+03 5.593005e+01 +14 6484 -1.634600e+02 5.069800e+02 +16 6484 -5.694700e+02 6.367500e+02 +0 6485 -1.374330e+03 7.665100e+02 +4 6485 -1.456400e+02 5.923500e+02 +5 6485 -1.007880e+03 8.742300e+02 +7 6485 -1.122530e+03 7.892800e+02 +10 6485 -1.487460e+03 6.263000e+01 +14 6485 -2.057100e+02 5.093800e+02 +15 6485 5.844500e+02 4.884600e+02 +16 6485 -6.229400e+02 6.360699e+02 +19 6485 2.103900e+02 7.808400e+02 +20 6485 -1.346370e+03 1.451599e+02 +0 6486 -1.473450e+03 7.796600e+02 +4 6486 -1.979800e+02 5.976100e+02 +5 6486 -1.081860e+03 8.705601e+02 +7 6486 -1.212050e+03 8.063300e+02 +10 6486 -1.536120e+03 7.956995e+01 +14 6486 -2.557400e+02 5.172000e+02 +15 6486 5.235601e+02 4.934900e+02 +16 6486 -6.842000e+02 6.438101e+02 +19 6486 1.131500e+02 7.866500e+02 +20 6486 -1.417030e+03 1.609500e+02 +0 6487 -1.536420e+03 8.017300e+02 +4 6487 -2.316300e+02 6.091400e+02 +5 6487 -1.132170e+03 8.787900e+02 +7 6487 -1.269790e+03 8.291000e+02 +10 6487 -1.631260e+03 1.073000e+02 +14 6487 -2.864300e+02 5.290500e+02 +15 6487 4.845200e+02 5.047400e+02 +16 6487 -7.236400e+02 6.581400e+02 +19 6487 5.271997e+01 8.023300e+02 +20 6487 -1.462630e+03 1.802000e+02 +0 6488 -1.404790e+03 8.143700e+02 +4 6488 -1.635500e+02 6.172500e+02 +5 6488 -1.039800e+03 9.061899e+02 +7 6488 -1.153400e+03 8.292700e+02 +10 6488 -1.514590e+03 1.016400e+02 +14 6488 -2.224300e+02 5.323400e+02 +15 6488 5.631000e+02 5.153900e+02 +16 6488 -6.439800e+02 6.633900e+02 +19 6488 1.774100e+02 8.238700e+02 +20 6488 -1.370180e+03 1.762300e+02 +0 6489 1.116080e+03 2.343201e+02 +16 6489 6.893400e+02 4.185100e+02 +0 6490 9.610701e+02 2.369399e+02 +16 6490 6.202900e+02 4.015800e+02 +0 6491 1.569750e+03 2.461799e+02 +16 6491 9.655800e+02 3.823700e+02 +0 6492 -1.361780e+03 2.642600e+02 +19 6492 2.449000e+02 2.926000e+02 +0 6493 -8.830400e+02 3.521400e+02 +14 6493 -1.379001e+01 3.089300e+02 +19 6493 6.593899e+02 3.938900e+02 +0 6494 -9.221700e+02 4.277300e+02 +16 6494 -4.442100e+02 4.601200e+02 +0 6495 -1.451770e+03 6.591600e+02 +7 6495 -1.184300e+03 7.034800e+02 +10 6495 -1.558550e+03 -1.457996e+01 +15 6495 5.400000e+02 4.228500e+02 +16 6495 -6.637800e+02 5.722300e+02 +19 6495 1.411100e+02 6.701500e+02 +0 6496 -1.400570e+03 6.613101e+02 +4 6496 -1.569399e+02 5.356300e+02 +5 6496 -1.011560e+03 7.920100e+02 +7 6496 -1.139910e+03 7.025601e+02 +10 6496 -1.513120e+03 -1.737000e+01 +14 6496 -2.179600e+02 4.594200e+02 +15 6496 5.706300e+02 4.244000e+02 +16 6496 -6.334600e+02 5.729200e+02 +19 6496 1.897100e+02 6.753700e+02 +20 6496 -1.364610e+03 8.281006e+01 +0 6497 -1.624040e+03 6.864200e+02 +19 6497 -2.510999e+01 6.820300e+02 +0 6498 -1.449940e+03 7.646600e+02 +4 6498 -1.853300e+02 5.899399e+02 +5 6498 -1.062640e+03 8.628600e+02 +7 6498 -1.190410e+03 7.912300e+02 +10 6498 -1.555620e+03 6.752002e+01 +14 6498 -2.431200e+02 5.094200e+02 +15 6498 5.380000e+02 4.848600e+02 +16 6498 -6.691900e+02 6.344301e+02 +19 6498 1.363600e+02 7.724000e+02 +20 6498 -1.400290e+03 1.491500e+02 +0 6499 -1.495900e+03 7.616200e+02 +4 6499 -2.088800e+02 5.880800e+02 +5 6499 -1.094600e+03 8.550200e+02 +7 6499 -1.231740e+03 7.918201e+02 +10 6499 -1.597680e+03 6.992004e+01 +14 6499 -2.658000e+02 5.088000e+02 +15 6499 5.103101e+02 4.820100e+02 +16 6499 -6.972600e+02 6.329399e+02 +19 6499 9.233997e+01 7.662200e+02 +20 6499 -1.433450e+03 1.510901e+02 +0 6500 -1.446040e+03 8.041799e+02 +4 6500 -1.849600e+02 6.116600e+02 +5 6500 -1.067580e+03 8.924900e+02 +7 6500 -1.189570e+03 8.279500e+02 +10 6500 -1.550740e+03 1.032500e+02 +15 6500 5.382900e+02 5.096500e+02 +16 6500 -6.687800e+02 6.591600e+02 +19 6500 1.379100e+02 8.123400e+02 +20 6500 -1.398790e+03 1.774700e+02 +0 6501 -1.467520e+03 8.481600e+02 +4 6501 -1.972700e+02 6.342900e+02 +5 6501 -1.090100e+03 9.212500e+02 +7 6501 -1.210180e+03 8.579299e+02 +10 6501 -1.569540e+03 1.302800e+02 +14 6501 -2.531700e+02 5.503600e+02 +15 6501 5.245500e+02 5.320200e+02 +16 6501 -6.846000e+02 6.847500e+02 +19 6501 1.155300e+02 8.513101e+02 +0 6502 -1.467520e+03 8.481600e+02 +4 6502 -1.972700e+02 6.342900e+02 +5 6502 -1.090100e+03 9.212500e+02 +7 6502 -1.210180e+03 8.579299e+02 +10 6502 -1.569540e+03 1.302800e+02 +14 6502 -2.531700e+02 5.503600e+02 +15 6502 5.245500e+02 5.320200e+02 +16 6502 -6.846000e+02 6.847500e+02 +19 6502 1.155300e+02 8.513101e+02 +0 6503 -8.412300e+02 3.409399e+02 +10 6503 -1.226460e+03 -2.525601e+02 +11 6503 -9.361100e+02 2.881500e+02 +18 6503 -1.336580e+03 1.256899e+02 +20 6503 -1.149330e+03 -9.107996e+01 +0 6504 -9.788600e+02 3.419099e+02 +19 6504 5.816600e+02 3.836400e+02 +0 6505 -1.519940e+03 3.417700e+02 +14 6505 -2.678600e+02 3.114100e+02 +0 6506 -1.411130e+03 3.881100e+02 +16 6506 -6.263000e+02 4.179600e+02 +0 6507 -1.269710e+03 4.819500e+02 +14 6507 -1.581800e+02 3.743900e+02 +16 6507 -5.519900e+02 4.729700e+02 +0 6508 -1.350200e+03 5.664199e+02 +7 6508 -1.090840e+03 6.247000e+02 +10 6508 -1.473310e+03 -9.313000e+01 +14 6508 -1.929200e+02 4.149700e+02 +16 6508 -5.991500e+02 5.198900e+02 +19 6508 2.413300e+02 5.880701e+02 +0 6509 -1.351300e+03 6.017200e+02 +4 6509 -1.295601e+02 5.061300e+02 +5 6509 -9.636200e+02 7.570000e+02 +7 6509 -1.094920e+03 6.534100e+02 +10 6509 -1.471810e+03 -6.534998e+01 +14 6509 -1.932600e+02 4.313000e+02 +15 6509 6.040601e+02 3.919700e+02 +16 6509 -6.007400e+02 5.400000e+02 +19 6509 2.404700e+02 6.211300e+02 +20 6509 -1.330940e+03 4.615991e+01 +0 6510 -1.372760e+03 8.030000e+02 +16 6510 -6.234100e+02 6.569301e+02 +0 6511 -1.461550e+03 9.376201e+02 +14 6511 -2.517500e+02 5.918800e+02 +15 6511 5.247800e+02 5.836700e+02 +19 6511 1.152800e+02 9.375900e+02 +20 6511 -1.411210e+03 2.546599e+02 +0 6512 -8.957900e+02 3.131699e+02 +15 6512 7.852000e+02 2.425700e+02 +16 6512 -4.230600e+02 3.945701e+02 +19 6512 5.413700e+02 3.703800e+02 +0 6513 -8.058800e+02 3.284199e+02 +15 6513 8.911300e+02 2.523300e+02 +19 6513 7.210901e+02 3.767500e+02 +0 6514 -7.627600e+02 3.582400e+02 +16 6514 -3.154700e+02 4.273000e+02 +19 6514 7.467100e+02 4.119800e+02 +0 6515 -1.362840e+03 5.860200e+02 +4 6515 -1.344000e+02 4.972900e+02 +5 6515 -9.703100e+02 7.438300e+02 +7 6515 -1.102190e+03 6.411000e+02 +10 6515 -1.480230e+03 -7.679004e+01 +14 6515 -1.979200e+02 4.241100e+02 +15 6515 5.974900e+02 3.824500e+02 +16 6515 -6.064600e+02 5.308900e+02 +19 6515 2.305100e+02 6.054800e+02 +20 6515 -1.336390e+03 3.731006e+01 +0 6516 -8.007500e+02 7.245601e+02 +14 6516 -1.932999e+01 5.000100e+02 +0 6517 -1.535860e+03 7.717400e+02 +4 6517 -2.299900e+02 5.926899e+02 +5 6517 -1.124530e+03 8.573199e+02 +7 6517 -1.267740e+03 8.013800e+02 +10 6517 -1.633830e+03 7.993005e+01 +14 6517 -2.852300e+02 5.139301e+02 +15 6517 4.860800e+02 4.866000e+02 +16 6517 -7.221400e+02 6.384800e+02 +19 6517 5.380005e+01 7.724800e+02 +20 6517 -1.461820e+03 1.587600e+02 +0 6518 -1.535860e+03 7.717400e+02 +4 6518 -2.299900e+02 5.926899e+02 +5 6518 -1.124530e+03 8.573199e+02 +7 6518 -1.267740e+03 8.013800e+02 +10 6518 -1.633830e+03 7.993005e+01 +14 6518 -2.852300e+02 5.139301e+02 +15 6518 4.860800e+02 4.866000e+02 +16 6518 -7.221400e+02 6.384800e+02 +19 6518 5.380005e+01 7.724800e+02 +20 6518 -1.461820e+03 1.587600e+02 +0 6519 -1.410870e+03 7.767900e+02 +4 6519 -1.650200e+02 5.970800e+02 +5 6519 -1.036540e+03 8.769600e+02 +7 6519 -1.155050e+03 7.990500e+02 +10 6519 -1.518440e+03 7.237000e+01 +14 6519 -2.237400e+02 5.144200e+02 +15 6519 5.620900e+02 4.928800e+02 +16 6519 -6.449400e+02 6.415800e+02 +19 6519 1.742300e+02 7.872800e+02 +20 6519 -1.371490e+03 1.530901e+02 +0 6520 -1.397460e+03 7.881899e+02 +4 6520 -1.583500e+02 6.037600e+02 +5 6520 -1.029510e+03 8.872100e+02 +7 6520 -1.143930e+03 8.086100e+02 +10 6520 -1.507430e+03 8.146997e+01 +14 6520 -2.174100e+02 5.199900e+02 +15 6520 5.700300e+02 5.008800e+02 +16 6520 -6.373100e+02 6.491500e+02 +19 6520 1.864100e+02 7.997900e+02 +20 6520 -1.362600e+03 1.601100e+02 +0 6521 -1.547740e+03 7.962800e+02 +4 6521 -2.377700e+02 6.060701e+02 +5 6521 -1.138160e+03 8.744500e+02 +7 6521 -1.283430e+03 8.239600e+02 +10 6521 -1.648380e+03 1.031300e+02 +14 6521 -2.928200e+02 5.258500e+02 +15 6521 4.769700e+02 5.009100e+02 +16 6521 -7.331000e+02 6.537200e+02 +19 6521 3.897998e+01 7.944800e+02 +20 6521 -1.473450e+03 1.772900e+02 +0 6522 -1.447360e+03 8.444900e+02 +4 6522 -1.856600e+02 6.324600e+02 +5 6522 -1.073930e+03 9.219800e+02 +7 6522 -1.190860e+03 8.580500e+02 +10 6522 -1.549410e+03 1.293000e+02 +14 6522 -2.422800e+02 5.476300e+02 +15 6522 5.376899e+02 5.320300e+02 +16 6522 -6.706000e+02 6.825699e+02 +19 6522 1.357000e+02 8.501600e+02 +20 6522 -1.397190e+03 1.972800e+02 +0 6523 -1.491490e+03 8.849500e+02 +4 6523 -2.103101e+02 6.530200e+02 +7 6523 -1.235340e+03 8.941000e+02 +10 6523 -1.590630e+03 1.649099e+02 +14 6523 -2.651900e+02 5.673800e+02 +15 6523 5.094301e+02 5.539800e+02 +16 6523 -7.021400e+02 7.061200e+02 +19 6523 9.054004e+01 8.851500e+02 +20 6523 -1.430150e+03 2.255200e+02 +0 6524 -1.443860e+03 8.871300e+02 +4 6524 -1.855000e+02 6.549500e+02 +7 6524 -1.192630e+03 8.930300e+02 +10 6524 -1.547990e+03 1.618101e+02 +14 6524 -2.413400e+02 5.678199e+02 +15 6524 5.382500e+02 5.571700e+02 +16 6524 -6.724100e+02 7.071801e+02 +19 6524 1.363800e+02 8.917700e+02 +20 6524 -1.396250e+03 2.230801e+02 +0 6525 1.114440e+03 1.059900e+02 +8 6525 2.487300e+02 8.565002e+01 +16 6525 6.940300e+02 3.340200e+02 +0 6526 -8.243400e+02 1.955000e+02 +19 6526 7.118701e+02 2.417000e+02 +0 6527 -1.331700e+03 3.633500e+02 +15 6527 6.184700e+02 2.526400e+02 +19 6527 2.669399e+02 3.893401e+02 +0 6528 -8.237600e+02 3.952900e+02 +16 6528 -3.837000e+02 4.482400e+02 +0 6529 -7.336200e+02 4.657600e+02 +4 6529 1.315000e+02 4.722200e+02 +7 6529 -7.451300e+02 5.815800e+02 +10 6529 -1.153990e+03 -1.465200e+02 +11 6529 -9.111200e+02 4.562200e+02 +14 6529 1.144000e+01 3.756100e+02 +15 6529 8.917500e+02 3.553000e+02 +16 6529 -3.297700e+02 4.999900e+02 +18 6529 -1.312900e+03 2.368301e+02 +19 6529 7.210701e+02 5.440000e+02 +0 6530 -1.412540e+03 5.023101e+02 +4 6530 -1.582500e+02 4.529900e+02 +5 6530 -9.922700e+02 6.769800e+02 +7 6530 -1.143410e+03 5.747000e+02 +10 6530 -1.528570e+03 -1.392300e+02 +15 6530 5.691600e+02 3.324200e+02 +16 6530 -6.330500e+02 4.820800e+02 +19 6530 1.847900e+02 5.209500e+02 +20 6530 -1.372200e+03 -1.146997e+01 +0 6531 -7.525900e+02 5.806300e+02 +19 6531 6.917500e+02 6.652600e+02 +0 6532 -7.778700e+02 5.927900e+02 +11 6532 -9.074500e+02 5.675500e+02 +0 6533 -1.559710e+03 6.851899e+02 +19 6533 3.418005e+01 6.876200e+02 +0 6534 -1.262620e+03 7.041000e+02 +14 6534 -1.561700e+02 4.782700e+02 +0 6535 -1.439800e+03 7.345900e+02 +14 6535 -2.376500e+02 4.950900e+02 +0 6536 -1.393140e+03 7.997400e+02 +4 6536 -1.557100e+02 6.104200e+02 +5 6536 -1.027040e+03 8.972800e+02 +7 6536 -1.140420e+03 8.193300e+02 +10 6536 -1.502890e+03 9.088000e+01 +14 6536 -2.147500e+02 5.258400e+02 +15 6536 5.728500e+02 5.084600e+02 +16 6536 -6.356600e+02 6.564700e+02 +19 6536 1.907000e+02 8.121600e+02 +20 6536 -1.359000e+03 1.678700e+02 +0 6537 -1.570100e+03 8.106899e+02 +19 6537 1.793994e+01 8.073800e+02 +0 6538 -1.570100e+03 8.106899e+02 +4 6538 -2.501801e+02 6.130300e+02 +5 6538 -1.156430e+03 8.820601e+02 +7 6538 -1.304440e+03 8.360800e+02 +10 6538 -1.668410e+03 1.151000e+02 +14 6538 -3.040200e+02 5.328500e+02 +15 6538 4.628000e+02 5.078600e+02 +16 6538 -7.471300e+02 6.622100e+02 +19 6538 1.793994e+01 8.073800e+02 +20 6538 -1.491170e+03 1.858401e+02 +0 6539 -1.277860e+03 8.285900e+02 +4 6539 -1.050400e+02 6.312100e+02 +5 6539 -9.560400e+02 9.355601e+02 +7 6539 -1.065400e+03 8.442800e+02 +10 6539 -1.430430e+03 1.093300e+02 +14 6539 -1.704900e+02 5.383101e+02 +15 6539 6.297100e+02 5.319399e+02 +16 6539 -5.802300e+02 6.778400e+02 +19 6539 2.870601e+02 8.499700e+02 +0 6540 -1.567340e+03 8.394200e+02 +4 6540 -2.494399e+02 6.292800e+02 +7 6540 -1.304280e+03 8.600200e+02 +10 6540 -1.665370e+03 1.366600e+02 +14 6540 -3.034300e+02 5.463199e+02 +15 6540 4.631600e+02 5.257000e+02 +16 6540 -7.476400e+02 6.795900e+02 +19 6540 1.860999e+01 8.332800e+02 +0 6541 -1.493560e+03 1.011150e+03 +14 6541 -2.781800e+02 6.283600e+02 +19 6541 6.534998e+01 1.004230e+03 +0 6542 -1.391960e+03 2.468005e+01 +15 6542 5.914600e+02 5.482001e+01 +0 6543 -1.434440e+03 3.838000e+01 +14 6543 -2.290400e+02 1.708700e+02 +0 6544 1.037060e+03 1.259700e+02 +16 6544 6.566200e+02 3.383700e+02 +0 6545 1.155460e+03 1.583201e+02 +8 6545 3.209100e+02 1.604800e+02 +13 6545 -1.004430e+03 5.640200e+02 +0 6546 -1.399170e+03 1.984500e+02 +16 6546 -6.100400e+02 3.091899e+02 +0 6547 -1.120750e+03 2.360701e+02 +10 6547 -1.320090e+03 -3.477000e+02 +14 6547 -9.688000e+01 2.593500e+02 +0 6548 -1.351510e+03 2.464099e+02 +14 6548 -1.921100e+02 2.660200e+02 +19 6548 2.532600e+02 2.746699e+02 +0 6549 -1.461450e+03 2.493201e+02 +14 6549 -2.415600e+02 2.682000e+02 +15 6549 5.470300e+02 1.839200e+02 +0 6550 -1.497010e+03 2.505100e+02 +14 6550 -2.563000e+02 2.689300e+02 +15 6550 5.281400e+02 1.839300e+02 +16 6550 -6.658200e+02 3.358201e+02 +19 6550 1.200400e+02 2.731300e+02 +0 6551 -1.379650e+03 3.439399e+02 +15 6551 5.937700e+02 2.402000e+02 +0 6552 -9.110500e+02 4.937100e+02 +14 6552 -2.073999e+01 3.769300e+02 +0 6553 -1.415160e+03 5.104099e+02 +15 6553 5.673199e+02 3.370200e+02 +0 6554 -9.207000e+02 6.047200e+02 +19 6554 6.200300e+02 6.518400e+02 +0 6555 -1.191410e+03 6.457000e+02 +7 6555 -9.771200e+02 6.877700e+02 +10 6555 -1.353130e+03 -3.803003e+01 +14 6555 -1.239800e+02 4.498101e+02 +15 6555 6.922900e+02 4.239900e+02 +19 6555 3.856801e+02 6.748101e+02 +0 6556 -1.296930e+03 6.531300e+02 +10 6556 -1.432630e+03 -3.002002e+01 +15 6556 6.308900e+02 4.226000e+02 +16 6556 -5.762100e+02 5.694200e+02 +0 6557 -1.564510e+03 6.751200e+02 +4 6557 -2.417900e+02 5.418101e+02 +5 6557 -1.128800e+03 7.831000e+02 +7 6557 -1.289630e+03 7.226700e+02 +10 6557 -1.663990e+03 7.630005e+00 +15 6557 4.720900e+02 4.296200e+02 +19 6557 3.062000e+01 6.771799e+02 +0 6558 -8.252600e+02 6.767400e+02 +10 6558 -1.179160e+03 -1.680054e+00 +16 6558 -3.490100e+02 6.059100e+02 +19 6558 6.898301e+02 7.319700e+02 +0 6559 -1.393930e+03 6.811600e+02 +4 6559 -1.530900e+02 5.469000e+02 +7 6559 -1.132330e+03 7.195400e+02 +10 6559 -1.504560e+03 -1.930054e+00 +14 6559 -2.131800e+02 4.692600e+02 +15 6559 5.760100e+02 4.374900e+02 +0 6560 -1.108320e+03 7.047000e+02 +7 6560 -9.253700e+02 7.371899e+02 +10 6560 -1.302850e+03 5.150024e+00 +14 6560 -9.295001e+01 4.767000e+02 +16 6560 -4.778500e+02 6.069100e+02 +19 6560 4.551801e+02 7.393800e+02 +0 6561 -1.304310e+03 7.250900e+02 +15 6561 6.260300e+02 4.666600e+02 +0 6562 -1.134760e+03 7.388700e+02 +14 6562 -1.042000e+02 4.931000e+02 +19 6562 4.280500e+02 7.711000e+02 +0 6563 -1.538500e+03 7.536600e+02 +4 6563 -2.310300e+02 5.832700e+02 +5 6563 -1.122860e+03 8.439500e+02 +7 6563 -1.270430e+03 7.866300e+02 +10 6563 -1.637220e+03 6.720996e+01 +14 6563 -2.867700e+02 5.054500e+02 +15 6563 4.854200e+02 4.762900e+02 +19 6563 5.135999e+01 7.548800e+02 +0 6564 -9.025200e+02 7.893201e+02 +14 6564 -1.277400e+02 5.450300e+02 +0 6565 -1.616560e+03 8.139100e+02 +14 6565 -3.334600e+02 5.350900e+02 +0 6566 -9.001100e+02 8.427800e+02 +19 6566 6.244500e+02 8.904200e+02 +0 6567 -1.478610e+03 8.661700e+02 +4 6567 -2.032800e+02 6.436200e+02 +5 6567 -1.100030e+03 9.344200e+02 +7 6567 -1.223820e+03 8.779100e+02 +10 6567 -1.581050e+03 1.495200e+02 +14 6567 -2.588300e+02 5.582400e+02 +15 6567 5.171700e+02 5.435500e+02 +16 6567 -6.938600e+02 6.952800e+02 +19 6567 1.023101e+02 8.680500e+02 +20 6567 -1.422020e+03 2.133700e+02 +0 6568 -1.247390e+03 9.544900e+02 +19 6568 2.603700e+02 9.780100e+02 +0 6569 -1.147460e+03 1.193994e+01 +15 6569 6.352000e+02 5.071997e+01 +16 6569 -5.552000e+02 2.093600e+02 +0 6570 -1.210300e+03 1.381995e+01 +15 6570 6.905400e+02 4.990002e+01 +0 6571 -1.424400e+03 1.777002e+01 +19 6571 1.937800e+02 5.009009e+01 +0 6572 -1.063710e+03 8.002002e+01 +10 6572 -1.285410e+03 -4.660699e+02 +11 6572 -9.813700e+02 4.619995e+00 +15 6572 7.694700e+02 9.122998e+01 +20 6572 -1.187070e+03 -2.558000e+02 +0 6573 -1.388500e+03 1.411000e+02 +14 6573 -2.068200e+02 2.175200e+02 +0 6574 -1.402660e+03 1.409900e+02 +14 6574 -2.146700e+02 2.125000e+02 +15 6574 5.817000e+02 1.220700e+02 +16 6574 -6.089900e+02 2.701600e+02 +19 6574 2.090100e+02 1.592300e+02 +0 6575 -1.387580e+03 1.644199e+02 +19 6575 2.238199e+02 1.933600e+02 +0 6576 -1.388140e+03 1.755300e+02 +14 6576 -2.069400e+02 2.333600e+02 +15 6576 5.909000e+02 1.421100e+02 +19 6576 2.230300e+02 2.041000e+02 +0 6577 -1.488650e+03 1.997600e+02 +14 6577 -2.525800e+02 2.453400e+02 +15 6577 5.322400e+02 1.553800e+02 +19 6577 1.279900e+02 2.243500e+02 +0 6578 -1.061530e+03 2.021200e+02 +14 6578 -7.264001e+01 2.434000e+02 +15 6578 7.695300e+02 1.636600e+02 +19 6578 5.184800e+02 2.407100e+02 +0 6579 -1.230990e+03 2.432800e+02 +14 6579 -1.399300e+02 2.635400e+02 +15 6579 6.778000e+02 1.844600e+02 +16 6579 -5.209600e+02 3.384000e+02 +0 6580 -1.623620e+03 2.451599e+02 +19 6580 -2.645699e+02 2.497500e+02 +0 6581 -1.432060e+03 2.485400e+02 +15 6581 5.619399e+02 1.842300e+02 +19 6581 1.762700e+02 2.733301e+02 +0 6582 -1.672790e+03 2.522200e+02 +19 6582 -1.861600e+02 2.609299e+02 +0 6583 -1.592370e+03 2.781100e+02 +16 6583 -7.361700e+02 3.507000e+02 +0 6584 -9.443000e+02 2.989700e+02 +19 6584 6.116400e+02 3.416899e+02 +0 6585 -1.111970e+03 3.154500e+02 +14 6585 -9.439001e+01 2.959100e+02 +0 6586 -8.147600e+02 3.205400e+02 +14 6586 6.640015e+00 2.962000e+02 +15 6586 8.875100e+02 2.470500e+02 +16 6586 -3.304100e+02 3.989000e+02 +19 6586 7.155300e+02 3.684700e+02 +0 6587 -1.308910e+03 3.730100e+02 +19 6587 2.875000e+02 4.000601e+02 +0 6588 -8.128000e+02 3.912700e+02 +10 6588 -1.205050e+03 -2.113700e+02 +14 6588 7.529999e+00 3.284200e+02 +15 6588 8.870699e+02 2.905400e+02 +20 6588 -1.133670e+03 -5.840002e+01 +0 6589 -1.067000e+03 4.733500e+02 +16 6589 -4.481100e+02 4.748101e+02 +19 6589 5.016100e+02 5.111100e+02 +0 6590 -1.410420e+03 4.875000e+02 +4 6590 -1.561300e+02 4.449399e+02 +5 6590 -9.871300e+02 6.666300e+02 +7 6590 -1.136070e+03 5.616600e+02 +10 6590 -1.520250e+03 -1.507300e+02 +14 6590 -2.193000e+02 3.782600e+02 +15 6590 5.718800e+02 3.232100e+02 +16 6590 -6.285000e+02 4.726000e+02 +19 6590 1.901500e+02 5.063000e+02 +20 6590 -1.366410e+03 -2.060999e+01 +0 6591 -1.388540e+03 4.985701e+02 +4 6591 -1.457400e+02 4.511699e+02 +5 6591 -9.740000e+02 6.772400e+02 +7 6591 -1.119590e+03 5.701600e+02 +10 6591 -1.504550e+03 -1.434200e+02 +14 6591 -2.098700e+02 3.832000e+02 +15 6591 5.841100e+02 3.302400e+02 +19 6591 2.093101e+02 5.182200e+02 +0 6592 -1.359760e+03 5.088101e+02 +4 6592 -1.316801e+02 4.570901e+02 +7 6592 -1.097550e+03 5.785701e+02 +10 6592 -1.481100e+03 -1.364100e+02 +14 6592 -1.968200e+02 3.877200e+02 +15 6592 6.005300e+02 3.370400e+02 +16 6592 -6.024800e+02 4.859900e+02 +19 6592 2.355400e+02 5.297900e+02 +20 6592 -1.336680e+03 -8.859985e+00 +0 6593 -1.378630e+03 5.206899e+02 +4 6593 -1.403199e+02 4.683800e+02 +5 6593 -9.709600e+02 6.942100e+02 +7 6593 -1.111550e+03 5.882700e+02 +10 6593 -1.493070e+03 -1.188900e+02 +14 6593 -2.044600e+02 3.933400e+02 +16 6593 -6.116800e+02 4.989500e+02 +19 6593 2.186100e+02 5.410400e+02 +0 6594 -9.281000e+02 5.344000e+02 +16 6594 -3.853400e+02 5.157400e+02 +0 6595 -1.137110e+03 5.335400e+02 +19 6595 4.362200e+02 5.667100e+02 +0 6596 -1.367900e+03 5.367100e+02 +4 6596 -1.358400e+02 4.713301e+02 +5 6596 -9.653900e+02 7.071100e+02 +7 6596 -1.104620e+03 6.009500e+02 +10 6596 -1.486660e+03 -1.147500e+02 +14 6596 -2.002400e+02 4.009299e+02 +15 6596 5.955200e+02 3.529200e+02 +16 6596 -6.073200e+02 5.019399e+02 +19 6596 2.282900e+02 5.566700e+02 +0 6597 -1.623680e+03 5.610100e+02 +19 6597 -7.471997e+01 5.587400e+02 +0 6598 -1.459740e+03 6.788700e+02 +19 6598 7.819995e+01 6.826300e+02 +0 6599 -1.405780e+03 6.876700e+02 +19 6599 1.824399e+02 7.002200e+02 +0 6600 -1.656450e+03 7.187500e+02 +14 6600 -3.446900e+02 4.902000e+02 +0 6601 -1.628660e+03 7.196899e+02 +15 6601 4.316700e+02 4.544000e+02 +0 6602 -1.269770e+03 8.181600e+02 +14 6602 -1.669000e+02 5.325100e+02 +16 6602 -5.753200e+02 6.712800e+02 +0 6603 -1.714720e+03 8.287300e+02 +14 6603 -3.752200e+02 5.438400e+02 +0 6604 -7.983900e+02 8.308700e+02 +14 6604 -1.941000e+01 5.346500e+02 +0 6605 -9.069300e+02 8.392700e+02 +19 6605 6.187600e+02 8.871400e+02 +0 6606 -7.594400e+02 8.545400e+02 +14 6606 -1.017999e+01 5.464700e+02 +16 6606 -3.599000e+02 7.318400e+02 +19 6606 6.863201e+02 9.172100e+02 +0 6607 -1.512940e+03 8.651600e+02 +4 6607 -2.207700e+02 6.427100e+02 +5 6607 -1.124160e+03 9.294100e+02 +7 6607 -1.254830e+03 8.791400e+02 +10 6607 -1.612280e+03 1.522600e+02 +14 6607 -2.757500e+02 5.582700e+02 +15 6607 4.967800e+02 5.420500e+02 +16 6607 -7.151000e+02 6.945300e+02 +19 6607 6.950000e+01 8.640400e+02 +20 6607 -1.446510e+03 2.156000e+02 +0 6608 -1.489990e+03 8.661100e+02 +4 6608 -2.086700e+02 6.434900e+02 +5 6608 -1.108350e+03 9.329900e+02 +7 6608 -1.234030e+03 8.787400e+02 +10 6608 -1.591790e+03 1.507100e+02 +14 6608 -2.640200e+02 5.583300e+02 +15 6608 5.106200e+02 5.432600e+02 +19 6608 9.163000e+01 8.669600e+02 +0 6609 -1.434570e+03 8.675500e+02 +4 6609 -1.798500e+02 6.450900e+02 +5 6609 -1.068710e+03 9.408600e+02 +7 6609 -1.183480e+03 8.764800e+02 +10 6609 -1.539900e+03 1.458600e+02 +14 6609 -2.368500e+02 5.581300e+02 +15 6609 5.444700e+02 5.457500e+02 +16 6609 -6.662800e+02 6.960400e+02 +19 6609 1.454100e+02 8.734600e+02 +20 6609 -1.389490e+03 2.105801e+02 +0 6610 -1.445790e+03 8.675900e+02 +4 6610 -1.859100e+02 6.450200e+02 +5 6610 -1.076950e+03 9.395500e+02 +7 6610 -1.194610e+03 8.771000e+02 +10 6610 -1.551650e+03 1.472000e+02 +14 6610 -2.426600e+02 5.584100e+02 +15 6610 5.373600e+02 5.454600e+02 +19 6610 1.338500e+02 8.724900e+02 +0 6611 -1.402450e+03 8.697900e+02 +4 6611 -1.622300e+02 6.464800e+02 +5 6611 -1.045820e+03 9.466801e+02 +7 6611 -1.153160e+03 8.761899e+02 +10 6611 -1.509390e+03 1.442900e+02 +14 6611 -2.203500e+02 5.586801e+02 +15 6611 5.650000e+02 5.480400e+02 +16 6611 -6.444400e+02 6.971500e+02 +19 6611 1.778400e+02 8.785800e+02 +0 6612 -1.515280e+03 8.723400e+02 +15 6612 4.963199e+02 5.457700e+02 +19 6612 6.985999e+01 8.710500e+02 +0 6613 -1.482080e+03 8.738201e+02 +4 6613 -2.046700e+02 6.474399e+02 +7 6613 -1.223400e+03 8.839100e+02 +10 6613 -1.580020e+03 1.552300e+02 +16 6613 -6.941900e+02 6.995200e+02 +19 6613 1.012400e+02 8.754000e+02 +0 6614 -1.459270e+03 8.745300e+02 +4 6614 -1.929301e+02 6.481799e+02 +5 6614 -1.087360e+03 9.428000e+02 +7 6614 -1.203260e+03 8.832100e+02 +10 6614 -1.558530e+03 1.532200e+02 +15 6614 5.301899e+02 5.491200e+02 +19 6614 1.231801e+02 8.781200e+02 +20 6614 -1.404650e+03 2.162800e+02 +0 6615 -1.459060e+03 8.811600e+02 +4 6615 -1.938400e+02 6.514700e+02 +5 6615 -1.087990e+03 9.481300e+02 +7 6615 -1.206060e+03 8.884100e+02 +10 6615 -1.560940e+03 1.586799e+02 +14 6615 -2.496100e+02 5.647700e+02 +15 6615 5.293101e+02 5.524200e+02 +16 6615 -6.823600e+02 7.035100e+02 +19 6615 1.213300e+02 8.841200e+02 +0 6616 -1.475540e+03 8.807100e+02 +4 6616 -2.020900e+02 6.510800e+02 +7 6616 -1.220800e+03 8.890500e+02 +10 6616 -1.576400e+03 1.600400e+02 +14 6616 -2.574000e+02 5.650300e+02 +15 6616 5.188000e+02 5.518300e+02 +19 6616 1.053700e+02 8.822500e+02 +0 6617 -1.401430e+03 1.072140e+03 +10 6617 -1.535160e+03 3.102000e+02 +20 6617 -1.395320e+03 3.426599e+02 +0 6618 -1.495990e+03 1.081100e+02 +14 6618 -2.555800e+02 2.033000e+02 +0 6619 -1.379290e+03 1.173900e+02 +14 6619 -2.036700e+02 2.067100e+02 +19 6619 2.322300e+02 1.463900e+02 +0 6620 9.670500e+02 1.794199e+02 +16 6620 6.226801e+02 3.658800e+02 +0 6621 -1.387310e+03 1.864600e+02 +14 6621 -2.066400e+02 2.384800e+02 +19 6621 2.240100e+02 2.149399e+02 +0 6622 -1.387310e+03 1.864600e+02 +14 6622 -2.066400e+02 2.384800e+02 +15 6622 5.913500e+02 1.484100e+02 +19 6622 2.240100e+02 2.149399e+02 +0 6623 -1.064740e+03 1.906699e+02 +19 6623 5.152200e+02 2.295100e+02 +0 6624 -7.030500e+02 2.220500e+02 +9 6624 3.284200e+02 -4.298999e+01 +10 6624 1.923000e+02 -5.329900e+02 +13 6624 2.803101e+02 -6.139001e+01 +0 6625 -1.658230e+03 2.243401e+02 +19 6625 -4.267004e+01 2.410000e+02 +0 6626 -1.449280e+03 2.273700e+02 +14 6626 -2.359200e+02 2.580000e+02 +0 6627 -1.064080e+03 2.286100e+02 +15 6627 7.677800e+02 1.799600e+02 +0 6628 -1.637250e+03 2.377300e+02 +19 6628 -2.356006e+01 2.548201e+02 +0 6629 -1.523990e+03 2.502800e+02 +14 6629 -2.697900e+02 2.691100e+02 +19 6629 9.288000e+01 2.718401e+02 +0 6630 -1.480320e+03 2.508600e+02 +19 6630 1.355699e+02 2.735300e+02 +0 6631 -1.400670e+03 2.614800e+02 +15 6631 5.817400e+02 1.919000e+02 +19 6631 2.054900e+02 2.872400e+02 +0 6632 -1.536870e+03 2.635601e+02 +19 6632 7.851001e+01 2.841200e+02 +0 6633 -9.245800e+02 2.715601e+02 +10 6633 -1.210020e+03 -3.184301e+02 +15 6633 8.365900e+02 2.115400e+02 +0 6634 -9.245800e+02 2.715601e+02 +19 6634 6.305901e+02 3.146100e+02 +0 6635 -1.458710e+03 3.287600e+02 +14 6635 -2.403400e+02 3.048900e+02 +19 6635 1.507800e+02 3.500601e+02 +0 6636 -1.479730e+03 3.304199e+02 +14 6636 -2.488500e+02 3.058300e+02 +15 6636 5.358000e+02 2.301700e+02 +19 6636 1.327800e+02 3.505100e+02 +0 6637 -1.451580e+03 3.317600e+02 +14 6637 -2.376600e+02 3.064500e+02 +19 6637 1.568900e+02 3.535200e+02 +0 6638 -1.465310e+03 3.327500e+02 +15 6638 5.435500e+02 2.324500e+02 +0 6639 -1.530190e+03 3.342100e+02 +14 6639 -2.734100e+02 3.080500e+02 +19 6639 8.357996e+01 3.521799e+02 +0 6640 -1.605970e+03 3.400500e+02 +15 6640 4.546000e+02 2.355500e+02 +19 6640 3.520020e+00 3.542400e+02 +0 6641 -9.335400e+02 3.405400e+02 +19 6641 6.197200e+02 3.841699e+02 +0 6642 -1.607590e+03 3.602800e+02 +19 6642 2.020020e+00 3.729199e+02 +0 6643 -1.498350e+03 3.645500e+02 +19 6643 1.144900e+02 3.826400e+02 +0 6644 -1.254470e+03 3.706100e+02 +19 6644 3.369100e+02 3.999600e+02 +0 6645 -1.351110e+03 3.750801e+02 +14 6645 -1.925000e+02 3.256400e+02 +16 6645 -5.910000e+02 4.103700e+02 +19 6645 2.496100e+02 4.002100e+02 +0 6646 -9.200400e+02 4.512100e+02 +16 6646 -3.785900e+02 4.685400e+02 +19 6646 6.277900e+02 4.958500e+02 +0 6647 -7.578100e+02 4.709800e+02 +14 6647 2.999878e-01 3.778100e+02 +0 6648 -1.577240e+03 4.748700e+02 +15 6648 4.695900e+02 3.135300e+02 +0 6649 -1.071710e+03 4.852400e+02 +19 6649 4.962900e+02 5.222900e+02 +0 6650 -8.823700e+02 5.249000e+02 +19 6650 6.562000e+02 5.727100e+02 +0 6651 -1.573920e+03 5.782300e+02 +15 6651 4.679700e+02 3.735601e+02 +0 6652 -1.573920e+03 5.782300e+02 +15 6652 4.679700e+02 3.735601e+02 +0 6653 -1.484270e+03 6.015801e+02 +16 6653 -6.804700e+02 5.389800e+02 +0 6654 -7.779900e+02 6.229800e+02 +19 6654 7.353799e+02 6.748700e+02 +0 6655 -1.532390e+03 6.987700e+02 +4 6655 -2.261899e+02 5.547700e+02 +7 6655 -1.211290e+03 7.383700e+02 +10 6655 -1.581450e+03 1.981006e+01 +15 6655 4.904000e+02 4.443800e+02 +16 6655 -7.152900e+02 5.954600e+02 +19 6655 6.042004e+01 7.023600e+02 +0 6656 -1.478430e+03 7.003400e+02 +15 6656 5.236000e+02 4.465701e+02 +0 6657 -1.430650e+03 7.055200e+02 +4 6657 -1.733500e+02 5.593900e+02 +5 6657 -1.037590e+03 8.224700e+02 +7 6657 -1.167400e+03 7.415900e+02 +10 6657 -1.537080e+03 2.063000e+01 +14 6657 -2.321600e+02 4.813400e+02 +15 6657 5.526801e+02 4.513400e+02 +19 6657 1.598300e+02 7.175900e+02 +0 6658 -1.566220e+03 7.163500e+02 +15 6658 4.697600e+02 4.535500e+02 +0 6659 -8.323100e+02 7.498800e+02 +15 6659 8.625601e+02 5.162200e+02 +19 6659 6.712300e+02 8.058600e+02 +0 6660 -1.225320e+03 7.577700e+02 +4 6660 -7.259998e+01 5.929500e+02 +7 6660 -1.011080e+03 7.806799e+02 +10 6660 -1.378920e+03 4.981995e+01 +15 6660 6.674700e+02 4.903000e+02 +20 6660 -1.263460e+03 1.369299e+02 +0 6661 -8.960300e+02 8.064000e+02 +15 6661 7.637300e+02 5.753900e+02 +16 6661 -4.523400e+02 7.127900e+02 +0 6662 -7.931600e+02 8.262200e+02 +15 6662 8.380900e+02 5.813101e+02 +19 6662 6.286799e+02 8.870800e+02 +0 6663 -9.051100e+02 8.488800e+02 +16 6663 -4.525600e+02 7.248500e+02 +0 6664 -1.434440e+03 8.606300e+02 +5 6664 -1.067270e+03 9.359700e+02 +10 6664 -1.538530e+03 1.407700e+02 +14 6664 -2.361900e+02 5.548700e+02 +0 6665 -8.936100e+02 8.648400e+02 +19 6665 6.284600e+02 9.137700e+02 +0 6666 -1.414010e+03 8.761500e+02 +4 6666 -1.692400e+02 6.496799e+02 +5 6666 -1.055770e+03 9.496899e+02 +7 6666 -1.160980e+03 8.819500e+02 +10 6666 -1.519660e+03 1.502900e+02 +14 6666 -2.263300e+02 5.619900e+02 +15 6666 5.565200e+02 5.514900e+02 +0 6667 -1.414010e+03 8.761500e+02 +4 6667 -1.692400e+02 6.496799e+02 +5 6667 -1.055770e+03 9.496899e+02 +7 6667 -1.160980e+03 8.819500e+02 +10 6667 -1.519660e+03 1.502900e+02 +14 6667 -2.263300e+02 5.619900e+02 +15 6667 5.565200e+02 5.514900e+02 +19 6667 1.660500e+02 8.837200e+02 +0 6668 -1.424990e+03 8.758800e+02 +15 6668 5.509100e+02 5.509100e+02 +16 6668 -6.586400e+02 7.005300e+02 +19 6668 1.564700e+02 8.826100e+02 +0 6669 -1.463610e+03 9.187800e+02 +7 6669 -1.213950e+03 9.220701e+02 +10 6669 -1.566410e+03 1.895701e+02 +15 6669 5.239600e+02 5.753700e+02 +0 6670 -1.488920e+03 1.044440e+03 +7 6670 -1.265640e+03 1.038150e+03 +10 6670 -1.611090e+03 2.962900e+02 +19 6670 7.140002e+01 1.039480e+03 +0 6671 -1.390320e+03 1.072670e+03 +10 6671 -1.524860e+03 3.087300e+02 +20 6671 -1.387230e+03 3.429099e+02 +0 6672 -9.741300e+02 5.206995e+01 +15 6672 8.166899e+02 7.622998e+01 +0 6673 -1.419770e+03 6.489001e+01 +15 6673 5.742900e+02 7.815997e+01 +19 6673 1.944700e+02 9.545996e+01 +0 6674 -1.451240e+03 7.068994e+01 +15 6674 5.542700e+02 8.165997e+01 +0 6675 1.701910e+03 8.595996e+01 +8 6675 1.006960e+03 7.240997e+01 +17 6675 -7.619600e+02 2.764000e+02 +0 6676 -1.443770e+03 9.648999e+01 +19 6676 1.697700e+02 1.258201e+02 +0 6677 -1.533470e+03 9.728003e+01 +19 6677 8.918994e+01 1.239500e+02 +0 6678 -1.491490e+03 9.748999e+01 +19 6678 1.296300e+02 1.255400e+02 +0 6679 -1.543410e+03 1.707300e+02 +19 6679 7.429004e+01 1.941899e+02 +0 6680 -1.403800e+03 1.917800e+02 +15 6680 5.805699e+02 1.515500e+02 +0 6681 -1.431590e+03 2.311300e+02 +19 6681 1.781000e+02 2.562600e+02 +0 6682 -1.680620e+03 2.323600e+02 +19 6682 -6.252002e+01 2.482100e+02 +0 6683 -1.551940e+03 2.363401e+02 +15 6683 4.904500e+02 1.761100e+02 +19 6683 6.170996e+01 2.569800e+02 +0 6684 -1.400740e+03 2.740000e+02 +15 6684 5.808101e+02 1.992200e+02 +0 6685 -8.263500e+02 2.810701e+02 +10 6685 -1.170530e+03 -3.074399e+02 +15 6685 8.816700e+02 2.220400e+02 +0 6686 4.989800e+02 2.813700e+02 +12 6686 -8.981400e+02 -4.355300e+02 +0 6687 -8.109900e+02 2.821300e+02 +19 6687 7.191699e+02 3.293800e+02 +0 6688 -9.196600e+02 3.088900e+02 +19 6688 6.339099e+02 3.525500e+02 +0 6689 -1.686500e+03 3.293700e+02 +19 6689 -7.321997e+01 3.398500e+02 +0 6690 -8.642800e+02 3.334000e+02 +19 6690 6.750901e+02 3.796599e+02 +0 6691 -1.278380e+03 3.575901e+02 +19 6691 3.154399e+02 3.859800e+02 +0 6692 -7.433300e+02 4.093000e+02 +19 6692 7.589900e+02 4.619700e+02 +0 6693 -9.196200e+02 4.145200e+02 +19 6693 6.299399e+02 4.591500e+02 +0 6694 1.567250e+03 4.479199e+02 +12 6694 -2.718700e+02 -2.900500e+02 +0 6695 -1.365890e+03 4.710801e+02 +19 6695 2.335500e+02 4.932500e+02 +0 6696 -1.030360e+03 4.750500e+02 +15 6696 7.806600e+02 3.294700e+02 +0 6697 -1.574460e+03 4.988201e+02 +15 6697 4.694500e+02 3.275000e+02 +0 6698 -8.110800e+02 5.042700e+02 +10 6698 -1.201010e+03 -1.240400e+02 +15 6698 8.871400e+02 3.605900e+02 +0 6699 -1.336060e+03 5.392700e+02 +15 6699 6.116000e+02 3.562000e+02 +0 6700 -1.719600e+03 5.490000e+02 +19 6700 -1.102000e+02 5.459700e+02 +0 6701 -1.496450e+03 5.660300e+02 +15 6701 5.152100e+02 3.683900e+02 +19 6701 9.883997e+01 5.765100e+02 +0 6702 -1.182610e+03 5.685400e+02 +19 6702 3.962900e+02 5.993700e+02 +0 6703 -1.708610e+03 5.719299e+02 +19 6703 -1.004600e+02 5.693600e+02 +0 6704 -1.679450e+03 5.752700e+02 +19 6704 -7.431995e+01 5.741000e+02 +0 6705 -1.163010e+03 6.304500e+02 +19 6705 4.187900e+02 6.619900e+02 +0 6706 -1.206580e+03 6.341699e+02 +19 6706 3.800300e+02 6.628600e+02 +0 6707 -1.504650e+03 6.494399e+02 +19 6707 9.033997e+01 6.568500e+02 +0 6708 -1.689620e+03 6.923700e+02 +15 6708 3.958000e+02 4.366700e+02 +19 6708 -8.884998e+01 6.844200e+02 +0 6709 -9.327900e+02 7.069500e+02 +19 6709 6.041000e+02 7.537500e+02 +0 6710 -1.517800e+03 7.442100e+02 +16 6710 -7.057800e+02 6.216799e+02 +0 6711 -1.474370e+03 7.454900e+02 +4 6711 -1.958000e+02 5.794700e+02 +7 6711 -1.204390e+03 7.754800e+02 +10 6711 -1.534020e+03 5.122998e+01 +19 6711 1.176899e+02 7.521400e+02 +0 6712 -1.420630e+03 7.725000e+02 +15 6712 5.561700e+02 4.904200e+02 +19 6712 1.643300e+02 7.822500e+02 +0 6713 -1.264030e+03 8.358400e+02 +19 6713 2.989800e+02 8.568800e+02 +0 6714 -1.459740e+03 8.553000e+02 +4 6714 -1.925000e+02 6.383700e+02 +5 6714 -1.084350e+03 9.288500e+02 +7 6714 -1.204150e+03 8.677000e+02 +10 6714 -1.562400e+03 1.392900e+02 +15 6714 5.297400e+02 5.381000e+02 +19 6714 1.222300e+02 8.594500e+02 +0 6715 -1.390430e+03 9.029800e+02 +15 6715 5.611100e+02 5.714600e+02 +0 6716 -1.356960e+03 1.071300e+02 +19 6716 -1.685100e+02 1.257800e+02 +0 6717 -1.463590e+03 1.994099e+02 +19 6717 1.505699e+02 2.249399e+02 +0 6718 -1.622590e+03 2.320000e+02 +19 6718 -8.630005e+00 2.504700e+02 +0 6719 -1.479430e+03 3.075601e+02 +19 6719 1.331000e+02 3.285300e+02 +0 6720 -8.568000e+02 3.173301e+02 +19 6720 6.822400e+02 3.634600e+02 +0 6721 -1.374630e+03 3.297100e+02 +19 6721 2.306700e+02 3.547500e+02 +0 6722 -1.475240e+03 3.315901e+02 +19 6722 1.383700e+02 3.524600e+02 +0 6723 -1.527130e+03 3.644500e+02 +19 6723 8.668005e+01 3.809700e+02 +0 6724 -1.645230e+03 3.769600e+02 +19 6724 -3.733997e+01 3.869199e+02 +0 6725 -8.532900e+02 4.256599e+02 +19 6725 6.820701e+02 4.735300e+02 +0 6726 -1.368190e+03 4.367600e+02 +19 6726 2.313300e+02 4.592600e+02 +0 6727 -1.433650e+03 6.548900e+02 +19 6727 1.036100e+02 6.612100e+02 +0 6728 -1.374970e+03 6.826899e+02 +7 6728 -1.118210e+03 7.202500e+02 +10 6728 -1.488830e+03 -1.729980e+00 +19 6728 2.138500e+02 6.986400e+02 +0 6729 -1.164640e+03 7.280701e+02 +19 6729 4.062000e+02 7.584500e+02 +0 6730 -1.132260e+03 7.406000e+02 +19 6730 4.813400e+02 7.690100e+02 +0 6731 -1.135450e+03 7.434800e+02 +19 6731 4.274399e+02 7.762800e+02 +0 6732 -1.413310e+03 7.477500e+02 +19 6732 1.770601e+02 7.587300e+02 +0 6733 -1.344220e+03 7.562900e+02 +7 6733 -1.098370e+03 7.797400e+02 +10 6733 -1.463550e+03 5.291003e+01 +20 6733 -1.327820e+03 1.378900e+02 +0 6734 -1.436750e+03 7.604100e+02 +19 6734 1.490000e+02 7.697700e+02 +0 6735 -1.419590e+03 7.817300e+02 +19 6735 1.649500e+02 7.915000e+02 +0 6736 -1.484990e+03 8.537000e+02 +19 6736 1.428000e+02 8.615300e+02 +0 6737 -1.533720e+03 8.787400e+02 +19 6737 5.131006e+01 8.752600e+02 +0 6738 -1.412820e+03 1.796997e+01 +19 6738 2.031100e+02 5.030005e+01 +0 6739 -1.671950e+03 2.375500e+02 +19 6739 -5.360999e+01 2.533201e+02 +0 6740 1.711670e+03 3.176200e+02 +17 6740 -7.519700e+02 6.246300e+02 +0 6741 -1.395240e+03 3.655100e+02 +19 6741 2.077300e+02 3.883000e+02 +0 6742 -1.379590e+03 4.513000e+02 +19 6742 2.224700e+02 4.728201e+02 +0 6743 -1.364040e+03 5.056400e+02 +19 6743 2.321300e+02 5.263600e+02 +0 6744 -1.402910e+03 6.571600e+02 +19 6744 1.888900e+02 6.717400e+02 +0 6745 -1.406060e+03 6.570500e+02 +19 6745 1.856200e+02 6.710400e+02 +0 6746 -1.074000e+03 7.251300e+02 +19 6746 4.874200e+02 7.619600e+02 +0 6747 -1.577930e+03 7.429299e+02 +19 6747 1.915002e+01 7.414100e+02 +0 6748 -1.242450e+03 7.806400e+02 +19 6748 3.299800e+02 8.045500e+02 +0 6749 -1.362330e+03 8.101100e+02 +19 6749 2.205900e+02 8.241200e+02 +0 6750 -1.528460e+03 8.512800e+02 +19 6750 9.454004e+01 8.543600e+02 +0 6751 -1.446440e+03 8.549200e+02 +19 6751 1.744500e+02 8.654600e+02 +0 6752 -1.418200e+03 8.910601e+02 +19 6752 1.617800e+02 8.978000e+02 +1 6753 9.108501e+02 -6.998999e+01 +17 6753 -1.022320e+03 2.799000e+02 +1 6754 -1.167340e+03 2.019099e+02 +20 6754 -4.435300e+02 -1.903800e+02 +1 6755 1.339830e+03 1.901000e+02 +17 6755 -6.600300e+02 4.812400e+02 +1 6756 1.096960e+03 -3.828003e+01 +17 6756 -8.642600e+02 2.952600e+02 +1 6757 1.374090e+03 1.156400e+02 +12 6757 -9.659998e+01 -5.253900e+02 +17 6757 -6.361500e+02 4.186100e+02 +1 6758 -5.932800e+02 4.229000e+02 +13 6758 -1.546310e+03 1.047550e+03 +1 6759 1.408270e+03 -3.733400e+02 +18 6759 1.347600e+02 -1.346300e+02 +1 6760 1.262400e+03 -3.734200e+02 +18 6760 9.753003e+01 -1.338400e+02 +1 6761 1.262400e+03 -3.734200e+02 +12 6761 -1.379500e+02 -6.880100e+02 +20 6761 9.182996e+01 -3.103600e+02 +1 6762 6.769600e+02 5.322998e+01 +17 6762 -1.279540e+03 4.426599e+02 +1 6763 1.185970e+03 1.321000e+02 +17 6763 -7.867400e+02 4.358800e+02 +1 6764 1.309740e+03 2.189500e+02 +13 6764 1.296290e+03 5.301000e+02 +1 6765 1.239600e+03 2.319199e+02 +12 6765 -1.384000e+02 -4.833000e+02 +13 6765 1.203870e+03 5.512600e+02 +18 6765 9.918005e+01 2.734998e+01 +1 6766 1.185490e+03 3.595801e+02 +17 6766 -7.828200e+02 6.300400e+02 +1 6767 -5.922400e+02 4.227800e+02 +13 6767 -1.546310e+03 1.047550e+03 +1 6768 1.439240e+03 -2.765000e+02 +17 6768 -5.951600e+02 9.553003e+01 +18 6768 1.426100e+02 -1.092700e+02 +20 6768 1.299200e+02 -2.885400e+02 +1 6769 1.415240e+03 -2.764900e+02 +17 6769 -6.123199e+02 9.582996e+01 +1 6770 1.415240e+03 -2.764900e+02 +17 6770 -6.123199e+02 9.582996e+01 +20 6770 1.257200e+02 -2.884200e+02 +1 6771 -1.165200e+02 -2.370000e+02 +18 6771 -3.221899e+02 -4.088000e+01 +1 6772 9.591201e+02 2.539978e+00 +17 6772 -9.797100e+02 3.407400e+02 +1 6773 1.386270e+03 1.534000e+02 +13 6773 1.396500e+03 4.366699e+02 +17 6773 -6.257500e+02 4.509900e+02 +18 6773 1.355100e+02 5.380005e+00 +1 6774 1.155460e+03 3.726200e+02 +12 6774 -1.647900e+02 -4.357200e+02 +17 6774 -8.070700e+02 6.408201e+02 +18 6774 7.806006e+01 6.616992e+01 +1 6775 1.342880e+03 3.770000e+02 +12 6775 -1.026500e+02 -4.350900e+02 +13 6775 1.353010e+03 7.526500e+02 +17 6775 -6.547000e+02 6.377300e+02 +18 6775 1.274900e+02 6.576001e+01 +1 6776 -4.495100e+02 3.888000e+02 +13 6776 -1.311010e+03 9.857000e+02 +1 6777 7.593401e+02 -3.754500e+02 +17 6777 -1.181000e+03 2.725000e+01 +1 6778 6.010999e+01 -3.179600e+02 +18 6778 -3.060100e+02 -1.022998e+01 +20 6778 -2.605000e+02 -2.056000e+02 +1 6779 6.238000e+01 -3.091500e+02 +6 6779 3.958400e+02 -2.696400e+02 +13 6779 -8.406400e+02 7.668994e+01 +16 6779 8.581899e+02 2.882600e+02 +1 6780 1.455950e+03 -6.718994e+01 +12 6780 -7.256995e+01 -5.860300e+02 +1 6781 1.244090e+03 9.400024e-01 +13 6781 1.197270e+03 2.287000e+02 +1 6782 -7.832996e+01 3.284998e+01 +13 6782 -9.288900e+02 6.395601e+02 +1 6783 8.828799e+02 6.165002e+01 +17 6783 -1.046680e+03 3.968800e+02 +1 6784 -5.012800e+02 3.602100e+02 +13 6784 -1.475690e+03 1.020060e+03 +1 6785 1.116710e+03 3.798101e+02 +17 6785 -8.380400e+02 6.498700e+02 +1 6786 1.356630e+03 3.964900e+02 +17 6786 -6.430500e+02 6.552900e+02 +1 6787 1.330420e+03 4.030801e+02 +17 6787 -6.646200e+02 6.631200e+02 +1 6788 1.167660e+03 -3.613800e+02 +17 6788 -8.098100e+02 2.635999e+01 +1 6789 9.343201e+02 -2.491200e+02 +17 6789 -1.004270e+03 1.262800e+02 +1 6790 -6.529000e+02 -1.132400e+02 +13 6790 -1.521900e+03 1.353600e+02 +1 6791 1.053300e+03 -9.573999e+01 +17 6791 -9.000300e+02 2.503900e+02 +1 6792 1.354210e+03 -5.743005e+01 +13 6792 1.343360e+03 1.451500e+02 +17 6792 -6.551899e+02 2.751100e+02 +1 6793 1.288300e+03 -5.314001e+01 +13 6793 1.253580e+03 1.522900e+02 +17 6793 -7.088300e+02 2.801500e+02 +1 6794 7.742800e+02 2.030801e+02 +17 6794 -1.162050e+03 5.565701e+02 +1 6795 1.295480e+03 2.060701e+02 +13 6795 1.275040e+03 5.106699e+02 +1 6796 1.474350e+03 2.594600e+02 +17 6796 -5.499500e+02 5.557500e+02 +1 6797 1.346590e+03 4.050500e+02 +17 6797 -6.504600e+02 6.634000e+02 +1 6798 1.301770e+03 4.150100e+02 +13 6798 1.300310e+03 8.096700e+02 +1 6799 -5.840300e+02 4.231699e+02 +13 6799 -1.537620e+03 1.049450e+03 +1 6800 1.307660e+03 4.416000e+02 +13 6800 1.309820e+03 8.478900e+02 +1 6801 1.193760e+03 4.898101e+02 +12 6801 -5.633997e+01 -2.921500e+02 +18 6801 1.444100e+02 1.795701e+02 +1 6802 1.180670e+03 4.899700e+02 +12 6802 -6.216003e+01 -2.921300e+02 +17 6802 -8.143900e+02 9.364700e+02 +18 6802 1.385800e+02 1.790901e+02 +20 6802 1.223600e+02 -4.141003e+01 +1 6803 1.365630e+03 -3.750601e+02 +17 6803 -6.530200e+02 1.519995e+01 +1 6804 1.173020e+03 -3.548800e+02 +17 6804 -8.058000e+02 3.171997e+01 +1 6805 1.364110e+03 -3.531700e+02 +17 6805 -6.537900e+02 3.278003e+01 +1 6806 -6.570800e+02 -3.050800e+02 +13 6806 -1.526170e+03 -1.466000e+02 +1 6807 1.399860e+03 -2.847100e+02 +17 6807 -6.238900e+02 8.842004e+01 +1 6808 1.449120e+03 -2.584500e+02 +17 6808 -5.848800e+02 1.093500e+02 +1 6809 1.365330e+03 -2.473000e+02 +17 6809 -6.507200e+02 1.189800e+02 +1 6810 6.816003e+01 -2.456200e+02 +6 6810 4.176200e+02 -2.284300e+02 +13 6810 -8.780100e+02 2.767900e+02 +1 6811 1.449700e+03 -2.359000e+02 +17 6811 -5.836400e+02 1.275400e+02 +1 6812 -3.380800e+02 -1.940699e+02 +13 6812 -1.194220e+03 7.481995e+01 +1 6813 9.220500e+02 -1.812200e+02 +17 6813 -1.015330e+03 1.840300e+02 +1 6814 7.510400e+02 -1.165800e+02 +17 6814 -1.187100e+03 2.621599e+02 +1 6815 8.939800e+02 -7.373999e+01 +17 6815 -1.037170e+03 2.769600e+02 +1 6816 1.341230e+03 -6.333997e+01 +13 6816 1.325840e+03 1.363401e+02 +17 6816 -6.675400e+02 2.697200e+02 +1 6817 1.292100e+03 -5.882996e+01 +13 6817 1.259170e+03 1.440000e+02 +17 6817 -7.050200e+02 2.748700e+02 +1 6818 1.282980e+03 -5.897998e+01 +17 6818 -7.116200e+02 2.748700e+02 +1 6819 -7.777002e+01 3.887000e+01 +13 6819 -9.270100e+02 6.523101e+02 +1 6820 7.035100e+02 1.178500e+02 +17 6820 -1.225820e+03 4.774600e+02 +1 6821 1.202970e+03 1.307900e+02 +17 6821 -7.726100e+02 4.341500e+02 +1 6822 -7.102100e+02 1.685701e+02 +13 6822 -1.580410e+03 5.388201e+02 +1 6823 8.600200e+02 1.896300e+02 +17 6823 -1.064660e+03 5.101200e+02 +1 6824 -6.327500e+02 2.783201e+02 +13 6824 -1.485440e+03 7.144200e+02 +1 6825 1.293590e+03 3.380801e+02 +13 6825 1.284980e+03 7.006700e+02 +1 6826 1.225070e+03 3.433000e+02 +13 6826 1.190250e+03 7.088900e+02 +17 6826 -7.504700e+02 6.153301e+02 +1 6827 1.215220e+03 3.431200e+02 +17 6827 -7.589100e+02 6.157400e+02 +1 6828 9.532500e+02 4.879299e+02 +20 6828 5.857996e+01 -4.025000e+01 +1 6829 1.409000e+03 -2.852700e+02 +17 6829 -6.169900e+02 8.755005e+01 +1 6830 1.395880e+03 -2.550500e+02 +17 6830 -6.269800e+02 1.127900e+02 +1 6831 1.484850e+03 -2.394399e+02 +13 6831 1.506310e+03 -1.114600e+02 +17 6831 -5.567800e+02 1.244200e+02 +1 6832 1.475300e+03 -2.347400e+02 +17 6832 -5.637200e+02 1.284399e+02 +1 6833 1.480960e+03 -2.310100e+02 +17 6833 -5.594000e+02 1.314900e+02 +1 6834 -4.449399e+02 -1.763700e+02 +13 6834 -1.304070e+03 7.756006e+01 +1 6835 -1.535200e+02 -7.806995e+01 +13 6835 -1.016460e+03 3.698301e+02 +1 6836 1.339700e+03 -5.819995e+01 +13 6836 1.323190e+03 1.436000e+02 +1 6837 1.226450e+03 -5.562000e+01 +13 6837 1.169750e+03 1.496899e+02 +17 6837 -7.573400e+02 2.784399e+02 +1 6838 1.357600e+03 -4.912000e+01 +13 6838 1.348600e+03 1.560801e+02 +17 6838 -6.523700e+02 2.827000e+02 +1 6839 1.146900e+03 -3.968994e+01 +17 6839 -8.236100e+02 2.949399e+02 +1 6840 1.090170e+03 -3.397998e+01 +17 6840 -8.683400e+02 2.995100e+02 +1 6841 1.214530e+03 -5.690002e+00 +17 6841 -7.653000e+02 3.197600e+02 +1 6842 -4.921200e+02 1.257001e+01 +13 6842 -1.342210e+03 3.580100e+02 +1 6843 -4.278800e+02 4.715991e+01 +13 6843 -1.294000e+03 4.443101e+02 +1 6844 -4.652700e+02 6.252002e+01 +13 6844 -1.331090e+03 4.549600e+02 +1 6845 1.228880e+03 1.488900e+02 +13 6845 1.185860e+03 4.345601e+02 +1 6846 -5.561600e+02 1.910801e+02 +13 6846 -1.410600e+03 6.108500e+02 +1 6847 9.636799e+02 2.560100e+02 +17 6847 -9.720900e+02 5.566400e+02 +1 6848 8.480300e+02 2.956400e+02 +17 6848 -1.078220e+03 6.088900e+02 +1 6849 -6.372400e+02 3.081699e+02 +13 6849 -1.500210e+03 7.664299e+02 +1 6850 -6.337800e+02 3.338600e+02 +13 6850 -1.495540e+03 8.060800e+02 +1 6851 1.044830e+03 3.386000e+02 +17 6851 -9.008000e+02 6.207900e+02 +1 6852 1.228370e+03 3.479700e+02 +17 6852 -7.475700e+02 6.192800e+02 +1 6853 1.228370e+03 3.479700e+02 +13 6853 1.195010e+03 7.156899e+02 +1 6854 -4.230300e+02 3.776400e+02 +13 6854 -1.283130e+03 9.806001e+02 +1 6855 -7.651200e+02 3.829500e+02 +13 6855 -1.610370e+03 8.174600e+02 +1 6856 4.580005e+01 -3.104700e+02 +6 6856 3.840200e+02 -2.703600e+02 +13 6856 -8.811100e+02 7.329004e+01 +1 6857 1.396430e+03 -2.810000e+02 +17 6857 -6.265200e+02 9.194995e+01 +1 6858 1.270380e+03 -2.571100e+02 +17 6858 -7.262900e+02 1.120300e+02 +1 6859 9.753000e+02 -2.532200e+02 +17 6859 -9.686000e+02 1.205100e+02 +1 6860 -1.666300e+02 -2.052000e+02 +13 6860 -1.020830e+03 1.179700e+02 +1 6861 -1.644600e+02 -2.024100e+02 +13 6861 -1.016850e+03 1.237300e+02 +1 6862 -1.644600e+02 -2.024100e+02 +13 6862 -1.016850e+03 1.237300e+02 +1 6863 9.290601e+02 -1.752300e+02 +17 6863 -1.009580e+03 1.885701e+02 +1 6864 -1.284399e+02 -1.624200e+02 +13 6864 -9.717200e+02 2.109399e+02 +1 6865 -7.940200e+02 -1.268199e+02 +13 6865 -1.650820e+03 8.901001e+01 +1 6866 7.856599e+02 -1.017600e+02 +17 6866 -1.153760e+03 2.749800e+02 +1 6867 8.961101e+02 -7.830005e+01 +17 6867 -1.036040e+03 2.726899e+02 +1 6868 9.754399e+02 -7.087000e+01 +17 6868 -9.661300e+02 2.735100e+02 +1 6869 1.229860e+03 -5.970996e+01 +17 6869 -7.544500e+02 2.747900e+02 +1 6870 1.348390e+03 -5.509998e+01 +13 6870 1.335860e+03 1.472800e+02 +1 6871 1.342430e+03 -5.432996e+01 +13 6871 1.326040e+03 1.492900e+02 +17 6871 -6.653101e+02 2.784299e+02 +1 6872 1.264940e+03 -4.244995e+01 +13 6872 1.222790e+03 1.671500e+02 +1 6873 -1.332300e+02 -3.623999e+01 +13 6873 -1.039240e+03 5.030200e+02 +1 6874 1.168340e+03 -6.700012e+00 +17 6874 -8.039100e+02 3.198800e+02 +1 6875 -7.388000e+01 3.059009e+01 +13 6875 -9.200000e+02 6.341799e+02 +1 6876 -7.710999e+01 3.062000e+01 +13 6876 -9.260300e+02 6.357300e+02 +1 6877 -7.483997e+01 3.445996e+01 +13 6877 -9.208800e+02 6.435800e+02 +1 6878 -7.483997e+01 3.445996e+01 +13 6878 -9.208800e+02 6.435800e+02 +1 6879 6.607300e+02 9.883008e+01 +17 6879 -1.293990e+03 4.906200e+02 +1 6880 8.785701e+02 1.087100e+02 +17 6880 -1.048800e+03 4.356899e+02 +1 6881 1.042450e+03 1.269000e+02 +17 6881 -9.063800e+02 4.389399e+02 +1 6882 1.176580e+03 1.309800e+02 +17 6882 -7.934200e+02 4.350200e+02 +1 6883 -1.772200e+02 1.341400e+02 +13 6883 -1.124930e+03 8.480100e+02 +1 6884 1.203040e+03 1.458301e+02 +17 6884 -7.725200e+02 4.474399e+02 +1 6885 1.410700e+03 1.515601e+02 +13 6885 1.428710e+03 4.305901e+02 +1 6886 7.474399e+02 2.304199e+02 +17 6886 -1.186660e+03 5.828000e+02 +1 6887 -4.233800e+02 2.361599e+02 +13 6887 -1.284490e+03 7.486100e+02 +1 6888 1.298260e+03 2.465801e+02 +17 6888 -6.935300e+02 5.312400e+02 +1 6889 9.649399e+02 2.594099e+02 +17 6889 -9.703600e+02 5.595300e+02 +1 6890 -5.402200e+02 2.914800e+02 +13 6890 -1.384970e+03 7.658000e+02 +1 6891 9.589399e+02 3.194600e+02 +17 6891 -9.750900e+02 6.121799e+02 +1 6892 1.159260e+03 3.273800e+02 +17 6892 -8.049900e+02 6.042000e+02 +1 6893 1.196200e+03 3.284500e+02 +17 6893 -7.742900e+02 6.037900e+02 +1 6894 1.203990e+03 4.925000e+02 +17 6894 -7.864800e+02 9.406499e+02 +1 6895 1.468060e+03 -2.234500e+02 +13 6895 1.484210e+03 -8.755005e+01 +1 6896 -1.196000e+02 -1.204200e+02 +13 6896 -9.706900e+02 2.956799e+02 +1 6897 4.770000e+02 -6.941003e+01 +13 6897 1.669800e+02 4.333301e+02 +1 6898 -5.146200e+02 -5.204004e+01 +13 6898 -1.371220e+03 2.542700e+02 +1 6899 -1.150000e+02 -4.212000e+01 +13 6899 -1.002500e+03 4.913900e+02 +1 6900 -9.858997e+01 9.900024e+00 +13 6900 -9.699300e+02 5.948201e+02 +1 6901 -1.528600e+02 1.153998e+01 +13 6901 -1.076760e+03 5.999000e+02 +1 6902 -1.055300e+02 1.252002e+01 +13 6902 -9.836000e+02 5.997800e+02 +1 6903 -9.395996e+01 2.100000e+01 +13 6903 -9.601700e+02 6.170400e+02 +1 6904 -3.401801e+02 4.388000e+01 +13 6904 -1.191620e+03 4.685200e+02 +1 6905 -1.240200e+02 8.803003e+01 +13 6905 -1.019990e+03 7.560200e+02 +1 6906 -1.683600e+02 1.340300e+02 +13 6906 -1.107220e+03 8.484900e+02 +1 6907 1.347720e+03 1.367000e+02 +13 6907 1.343790e+03 4.130801e+02 +1 6908 1.230420e+03 1.424600e+02 +17 6908 -7.503500e+02 4.445000e+02 +1 6909 -1.911600e+02 1.600300e+02 +13 6909 -1.163470e+03 9.124500e+02 +1 6910 -3.861600e+02 1.802800e+02 +13 6910 -1.248350e+03 6.787000e+02 +1 6911 1.305870e+03 1.900300e+02 +13 6911 1.291560e+03 4.892400e+02 +1 6912 8.308999e+02 2.545400e+02 +17 6912 -1.096890e+03 5.799399e+02 +1 6913 1.230050e+03 3.410100e+02 +13 6913 1.197550e+03 7.051899e+02 +1 6914 -4.187900e+02 3.803700e+02 +13 6914 -1.276040e+03 9.863799e+02 +1 6915 -7.779700e+02 4.475601e+02 +13 6915 -1.639220e+03 9.191201e+02 +2 6916 6.236000e+02 8.415997e+01 +17 6916 -1.172980e+03 4.564299e+02 +2 6917 7.200100e+02 3.195500e+02 +17 6917 -1.059310e+03 8.172300e+02 +2 6918 6.876400e+02 2.313600e+02 +17 6918 -1.064170e+03 6.819800e+02 +2 6919 -3.412500e+02 4.621002e+01 +12 6919 -9.096000e+02 -5.315800e+02 +2 6920 5.675300e+02 1.071400e+02 +17 6920 -1.274580e+03 4.952900e+02 +2 6921 6.058000e+02 1.212400e+02 +17 6921 -1.200890e+03 5.215601e+02 +2 6922 6.456899e+02 2.164500e+02 +17 6922 -1.126620e+03 6.669800e+02 +2 6923 -4.474100e+02 -2.164400e+02 +20 6923 -4.763000e+02 -3.145500e+02 +2 6924 5.751600e+02 -3.413000e+01 +17 6924 -1.258050e+03 2.789700e+02 +2 6925 4.980500e+02 5.708002e+01 +17 6925 -1.405740e+03 4.239500e+02 +2 6926 5.771500e+02 6.792999e+01 +17 6926 -1.251420e+03 4.361100e+02 +2 6927 6.436100e+02 7.378003e+01 +17 6927 -1.137840e+03 4.409500e+02 +2 6928 -4.297500e+02 8.477002e+01 +12 6928 -9.613600e+02 -5.094000e+02 +2 6929 5.852900e+02 1.842700e+02 +17 6929 -1.230350e+03 6.176500e+02 +2 6930 -4.882000e+02 3.971200e+02 +18 6930 -5.726000e+02 1.568201e+02 +2 6931 -3.088800e+02 4.632100e+02 +20 6931 -4.059100e+02 -3.156995e+01 +2 6932 -4.456400e+02 -1.908700e+02 +11 6932 2.120100e+02 -6.365002e+01 +20 6932 -4.741100e+02 -3.037700e+02 +2 6933 5.135100e+02 1.307000e+02 +17 6933 -1.371470e+03 5.353401e+02 +2 6934 5.643900e+02 1.472400e+02 +17 6934 -1.274530e+03 5.582100e+02 +2 6935 6.602100e+02 1.537200e+02 +17 6935 -1.108570e+03 5.671100e+02 +2 6936 5.463300e+02 1.674900e+02 +17 6936 -1.306930e+03 5.927000e+02 +2 6937 -5.760100e+02 3.281200e+02 +16 6937 2.811100e+02 4.445300e+02 +2 6938 5.359600e+02 -3.984900e+02 +20 6938 -2.627400e+02 -4.248199e+02 +2 6939 -4.339500e+02 -2.023900e+02 +11 6939 2.206300e+02 -7.166998e+01 +2 6940 -3.751600e+02 -7.289001e+01 +12 6940 -9.339400e+02 -6.049399e+02 +2 6941 5.880200e+02 -1.545001e+01 +17 6941 -1.231850e+03 3.082500e+02 +2 6942 5.179600e+02 3.328998e+01 +17 6942 -1.365600e+03 3.847300e+02 +2 6943 5.590699e+02 4.490002e+01 +17 6943 -1.284640e+03 4.009099e+02 +2 6944 6.539200e+02 6.142999e+01 +17 6944 -1.118640e+03 4.232300e+02 +2 6945 6.886899e+02 8.701001e+01 +17 6945 -1.060110e+03 4.607400e+02 +2 6946 5.969200e+02 8.695001e+01 +17 6946 -1.214950e+03 4.660601e+02 +2 6947 6.583800e+02 1.709400e+02 +17 6947 -1.111680e+03 5.877600e+02 +2 6948 5.842000e+02 2.243200e+02 +17 6948 -1.236520e+03 6.776400e+02 +2 6949 7.538600e+02 3.319300e+02 +12 6949 -1.438400e+02 -3.379500e+02 +17 6949 -1.006980e+03 8.333201e+02 +20 6949 6.620996e+01 -7.281006e+01 +2 6950 6.624800e+02 4.172300e+02 +17 6950 -1.151050e+03 9.744399e+02 +18 6950 2.957996e+01 1.877600e+02 +20 6950 2.946997e+01 -3.433997e+01 +2 6951 -4.723700e+02 4.464399e+02 +18 6951 -5.637700e+02 1.800000e+02 +2 6952 4.866300e+02 -2.038400e+02 +13 6952 -1.207650e+03 -9.344995e+01 +2 6953 -1.675900e+02 -1.990500e+02 +20 6953 -3.460300e+02 -3.022500e+02 +2 6954 -4.245100e+02 -8.622998e+01 +18 6954 -5.446800e+02 -7.190002e+01 +2 6955 5.812500e+02 1.073600e+02 +17 6955 -1.240990e+03 4.983401e+02 +2 6956 5.483600e+02 1.350800e+02 +17 6956 -1.305620e+03 5.415601e+02 +2 6957 5.967000e+02 2.353100e+02 +17 6957 -1.214020e+03 6.941899e+02 +2 6958 6.530200e+02 2.685300e+02 +17 6958 -1.154290e+03 7.423201e+02 +2 6959 7.086300e+02 2.804000e+02 +17 6959 -1.054040e+03 7.561600e+02 +2 6960 -4.348100e+02 3.032000e+02 +12 6960 -9.630400e+02 -3.782400e+02 +2 6961 7.032300e+02 3.418800e+02 +12 6961 -1.754200e+02 -3.308800e+02 +2 6962 7.720000e+02 3.668900e+02 +17 6962 -9.816900e+02 8.880601e+02 +2 6963 5.260500e+02 3.912700e+02 +11 6963 1.010200e+03 4.336899e+02 +2 6964 -7.429100e+02 4.407300e+02 +14 6964 4.361000e+02 3.432900e+02 +2 6965 5.100300e+02 -3.868500e+02 +13 6965 -1.177190e+03 -5.121000e+02 +2 6966 6.258101e+02 -3.264300e+02 +17 6966 -7.023600e+02 -1.636000e+02 +2 6967 -3.990100e+02 -2.090200e+02 +11 6967 2.451100e+02 -7.594000e+01 +18 6967 -5.335200e+02 -1.300300e+02 +2 6968 -4.958300e+02 -1.017200e+02 +12 6968 -1.009860e+03 -6.224000e+02 +20 6968 -4.929200e+02 -2.673900e+02 +2 6969 6.598000e+02 -3.348999e+01 +17 6969 -1.108040e+03 2.777500e+02 +2 6970 5.388800e+02 -3.178003e+01 +17 6970 -1.325010e+03 2.833600e+02 +2 6971 7.076000e+02 -2.360999e+01 +17 6971 -1.030800e+03 2.911899e+02 +2 6972 5.671200e+02 -1.273999e+01 +17 6972 -1.270420e+03 3.126599e+02 +2 6973 5.671200e+02 -1.273999e+01 +17 6973 -1.270420e+03 3.126599e+02 +2 6974 7.303500e+02 4.509003e+01 +17 6974 -9.956900e+02 3.937200e+02 +2 6975 5.927500e+02 5.564001e+01 +17 6975 -1.220210e+03 4.169800e+02 +2 6976 5.675800e+02 1.014300e+02 +17 6976 -1.268480e+03 4.896200e+02 +2 6977 7.629100e+02 1.127700e+02 +17 6977 -9.426500e+02 4.971500e+02 +2 6978 5.401899e+02 1.535000e+02 +17 6978 -1.321470e+03 5.710100e+02 +2 6979 6.801500e+02 1.616600e+02 +17 6979 -1.074260e+03 5.750200e+02 +2 6980 5.762500e+02 1.683200e+02 +17 6980 -1.255180e+03 5.908000e+02 +2 6981 6.319700e+02 1.865500e+02 +17 6981 -1.158670e+03 6.162900e+02 +2 6982 6.456300e+02 1.917500e+02 +17 6982 -1.131710e+03 6.241599e+02 +2 6983 6.949301e+02 2.018800e+02 +17 6983 -1.050440e+03 6.366200e+02 +2 6984 -2.419500e+02 2.492900e+02 +13 6984 -1.637750e+03 8.933800e+02 +2 6985 -1.408000e+02 2.929200e+02 +13 6985 -1.291390e+03 9.898701e+02 +2 6986 7.067000e+02 3.003500e+02 +17 6986 -1.057190e+03 7.870300e+02 +2 6987 5.178900e+02 3.452200e+02 +11 6987 9.992200e+02 3.926000e+02 +2 6988 -5.013600e+02 3.486600e+02 +16 6988 3.134000e+02 4.558900e+02 +2 6989 5.283900e+02 3.668800e+02 +11 6989 1.005790e+03 4.115200e+02 +17 6989 -1.363380e+03 9.048799e+02 +2 6990 7.427200e+02 3.677600e+02 +17 6990 -1.025820e+03 8.906201e+02 +2 6991 -6.809400e+02 3.893600e+02 +14 6991 4.568300e+02 3.261000e+02 +2 6992 -4.921000e+02 4.423300e+02 +18 6992 -5.738600e+02 1.783700e+02 +2 6993 6.598900e+02 4.430200e+02 +20 6993 2.879004e+01 -2.400000e+01 +2 6994 4.119800e+02 -3.945800e+02 +13 6994 -1.442720e+03 -5.184399e+02 +2 6995 5.019900e+02 -3.911700e+02 +13 6995 -1.200220e+03 -5.194800e+02 +2 6996 6.427000e+02 -3.690000e+02 +13 6996 -7.990800e+02 -4.855200e+02 +2 6997 6.168400e+02 -3.599200e+02 +13 6997 -8.521600e+02 -4.640601e+02 +2 6998 2.949100e+02 -3.309500e+02 +17 6998 -1.392630e+03 -1.792700e+02 +2 6999 3.465800e+02 -2.807500e+02 +17 6999 -1.306770e+03 -1.011400e+02 +2 7000 6.535601e+02 -3.892999e+01 +17 7000 -1.119600e+03 2.683900e+02 +2 7001 6.535601e+02 -3.892999e+01 +17 7001 -1.119600e+03 2.683900e+02 +2 7002 5.270800e+02 -3.423999e+01 +17 7002 -1.349480e+03 2.810100e+02 +2 7003 5.053700e+02 2.912000e+01 +17 7003 -1.392400e+03 3.791100e+02 +2 7004 5.053700e+02 2.912000e+01 +17 7004 -1.392400e+03 3.791100e+02 +2 7005 5.789900e+02 5.251001e+01 +17 7005 -1.247270e+03 4.114299e+02 +2 7006 5.537700e+02 9.619000e+01 +17 7006 -1.292490e+03 4.807300e+02 +2 7007 6.510800e+02 9.895996e+01 +17 7007 -1.121540e+03 4.808301e+02 +2 7008 7.506100e+02 1.068900e+02 +17 7008 -9.620900e+02 4.889700e+02 +2 7009 5.399200e+02 1.468100e+02 +17 7009 -1.322860e+03 5.600300e+02 +2 7010 6.000000e+02 1.961300e+02 +17 7010 -1.207340e+03 6.327200e+02 +2 7011 -4.878900e+02 4.483101e+02 +20 7011 -4.849700e+02 -4.335999e+01 +2 7012 4.144500e+02 -1.981700e+02 +13 7012 -1.373920e+03 -7.758997e+01 +2 7013 4.901899e+02 -1.893600e+02 +13 7013 -1.199820e+03 -5.971997e+01 +2 7014 3.354000e+02 -1.810400e+02 +13 7014 -9.936800e+02 -1.066400e+02 +2 7015 4.624200e+02 -1.765300e+02 +13 7015 -1.265820e+03 -2.873999e+01 +2 7016 4.624200e+02 -1.765300e+02 +13 7016 -1.265820e+03 -2.873999e+01 +2 7017 -4.562200e+02 -1.680900e+02 +11 7017 2.034301e+02 -4.738000e+01 +2 7018 4.611801e+02 -1.635800e+02 +13 7018 -1.260150e+03 -3.229980e+00 +2 7019 7.641899e+02 -1.460700e+02 +12 7019 -2.192300e+02 -6.506899e+02 +2 7020 -1.216200e+02 -8.950000e+01 +18 7020 -3.759900e+02 -6.379004e+01 +2 7021 -2.414100e+02 -8.550000e+01 +13 7021 -1.651640e+03 5.810999e+01 +2 7022 -2.508800e+02 -3.348999e+01 +13 7022 -1.677180e+03 1.893101e+02 +2 7023 6.657500e+02 1.059003e+01 +17 7023 -1.098930e+03 3.451500e+02 +2 7024 -2.446900e+02 1.221997e+01 +13 7024 -1.654750e+03 3.001100e+02 +2 7025 -1.040300e+02 3.113000e+01 +18 7025 -3.637900e+02 -3.479980e+00 +2 7026 5.465000e+02 3.672998e+01 +17 7026 -1.309270e+03 3.906400e+02 +2 7027 7.203500e+02 4.240997e+01 +17 7027 -1.010610e+03 3.918500e+02 +2 7028 7.782100e+02 8.259003e+01 +12 7028 -2.088000e+02 -5.120699e+02 +2 7029 -1.649300e+02 8.266998e+01 +18 7029 -4.041000e+02 1.589001e+01 +20 7029 -3.419301e+02 -1.845900e+02 +2 7030 6.528300e+02 8.492999e+01 +17 7030 -1.120540e+03 4.601300e+02 +2 7031 -2.124100e+02 1.023200e+02 +13 7031 -1.489100e+03 5.107800e+02 +2 7032 6.929399e+02 1.078700e+02 +17 7032 -1.051540e+03 4.921899e+02 +2 7033 5.922600e+02 1.123200e+02 +17 7033 -1.220280e+03 5.039299e+02 +2 7034 6.479301e+02 1.245500e+02 +17 7034 -1.129350e+03 5.204000e+02 +2 7035 -1.774300e+02 1.308000e+02 +13 7035 -1.435970e+03 5.898600e+02 +2 7036 -2.390200e+02 1.590700e+02 +13 7036 -1.628910e+03 6.658201e+02 +2 7037 6.333000e+02 1.739500e+02 +17 7037 -1.156650e+03 5.962400e+02 +2 7038 6.128600e+02 1.908000e+02 +17 7038 -1.187310e+03 6.236500e+02 +2 7039 -2.245700e+02 1.938200e+02 +13 7039 -1.588830e+03 7.530200e+02 +2 7040 5.936500e+02 2.090500e+02 +17 7040 -1.219530e+03 6.532900e+02 +2 7041 5.753199e+02 2.139300e+02 +17 7041 -1.256530e+03 6.621500e+02 +2 7042 -1.576000e+02 2.431500e+02 +13 7042 -1.346860e+03 8.677600e+02 +2 7043 6.971801e+02 3.371800e+02 +12 7043 -1.797100e+02 -3.343199e+02 +2 7044 -5.290900e+02 4.470200e+02 +18 7044 -5.908100e+02 1.811599e+02 +2 7045 5.013800e+02 -3.765800e+02 +13 7045 -1.199890e+03 -4.860200e+02 +2 7046 2.955900e+02 -3.260100e+02 +17 7046 -1.391990e+03 -1.717800e+02 +2 7047 -2.498800e+02 -1.862100e+02 +13 7047 -1.682490e+03 -1.928700e+02 +2 7048 4.649000e+02 -1.798900e+02 +13 7048 -1.258710e+03 -3.772998e+01 +2 7049 3.270800e+02 -1.801500e+02 +17 7049 -1.341720e+03 5.421997e+01 +2 7050 -2.659500e+02 -1.613400e+02 +12 7050 -8.584500e+02 -6.557000e+02 +2 7051 -5.988000e+01 -7.225000e+01 +13 7051 -9.443100e+02 5.375000e+01 +2 7052 5.012000e+02 -6.141998e+01 +17 7052 -1.402640e+03 2.392800e+02 +2 7053 -6.796002e+01 -4.577002e+01 +13 7053 -9.734500e+02 1.258300e+02 +2 7054 7.005500e+02 -3.994000e+01 +17 7054 -1.041910e+03 2.671400e+02 +2 7055 7.910100e+02 -3.662000e+01 +17 7055 -9.003300e+02 2.702100e+02 +2 7056 5.466100e+02 5.651001e+01 +17 7056 -1.308900e+03 4.197200e+02 +2 7057 -2.487700e+02 5.795001e+01 +13 7057 -1.666140e+03 4.147300e+02 +2 7058 -2.584600e+02 6.395001e+01 +13 7058 -1.696000e+03 4.311500e+02 +2 7059 5.084100e+02 6.632001e+01 +17 7059 -1.381720e+03 4.371100e+02 +2 7060 7.139301e+02 7.196002e+01 +17 7060 -1.020170e+03 4.369199e+02 +2 7061 -2.048300e+02 1.038500e+02 +13 7061 -1.518130e+03 5.250000e+02 +2 7062 6.749600e+02 1.283900e+02 +17 7062 -1.083140e+03 5.244399e+02 +2 7063 5.542200e+02 1.476700e+02 +17 7063 -1.295100e+03 5.602000e+02 +2 7064 -1.998000e+02 1.702000e+02 +13 7064 -1.503370e+03 6.891400e+02 +2 7065 -2.003800e+02 1.860000e+02 +13 7065 -1.515660e+03 7.311600e+02 +2 7066 7.902100e+02 1.953900e+02 +12 7066 -2.013800e+02 -4.436700e+02 +2 7067 -3.368000e+02 2.093600e+02 +12 7067 -9.013700e+02 -4.338800e+02 +2 7068 -3.368000e+02 2.093600e+02 +12 7068 -9.013700e+02 -4.338800e+02 +2 7069 5.791300e+02 2.172700e+02 +17 7069 -1.248180e+03 6.677300e+02 +2 7070 -2.218300e+02 2.450400e+02 +13 7070 -1.567960e+03 8.799600e+02 +2 7071 7.189600e+02 2.803800e+02 +17 7071 -1.037600e+03 7.563000e+02 +2 7072 -2.097900e+02 2.816200e+02 +13 7072 -1.430060e+03 9.634900e+02 +2 7073 7.211100e+02 2.854100e+02 +17 7073 -1.034380e+03 7.641600e+02 +2 7074 7.402100e+02 3.259400e+02 +17 7074 -1.028260e+03 8.259200e+02 +2 7075 6.993300e+02 4.342100e+02 +17 7075 -1.093320e+03 9.966101e+02 +2 7076 -2.130000e+02 -1.824900e+02 +13 7076 -1.564710e+03 -1.870500e+02 +2 7077 3.279500e+02 -1.768800e+02 +13 7077 -1.010410e+03 -9.593005e+01 +2 7078 -2.182900e+02 -1.755400e+02 +13 7078 -1.585720e+03 -1.687800e+02 +2 7079 -2.448100e+02 -1.547600e+02 +13 7079 -1.664010e+03 -1.165900e+02 +2 7080 2.078300e+02 -1.046400e+02 +13 7080 -5.763000e+02 -2.920044e+00 +2 7081 -1.568800e+02 -6.245001e+01 +13 7081 -1.375140e+03 1.048101e+02 +2 7082 -1.863800e+02 -3.742999e+01 +13 7082 -1.474870e+03 1.708301e+02 +2 7083 7.933500e+02 -3.344000e+01 +17 7083 -8.971900e+02 2.748800e+02 +2 7084 -7.890002e+01 -1.717999e+01 +13 7084 -1.007310e+03 1.976699e+02 +2 7085 -1.224100e+02 3.059003e+01 +13 7085 -1.241280e+03 3.309000e+02 +2 7086 5.500400e+02 5.564001e+01 +17 7086 -1.302540e+03 4.192400e+02 +2 7087 -1.760010e+00 7.363000e+01 +13 7087 -1.433610e+03 4.798301e+02 +2 7088 5.571600e+02 1.066100e+02 +17 7088 -1.287940e+03 4.974600e+02 +2 7089 6.730300e+02 1.356800e+02 +17 7089 -1.086720e+03 5.350801e+02 +2 7090 -1.771200e+02 1.499500e+02 +13 7090 -1.434680e+03 6.375100e+02 +2 7091 -1.825700e+02 1.514900e+02 +13 7091 -1.451340e+03 6.418500e+02 +2 7092 -2.342500e+02 1.634000e+02 +13 7092 -1.614050e+03 6.758600e+02 +2 7093 -2.656000e+02 1.708100e+02 +13 7093 -1.716530e+03 6.979100e+02 +2 7094 -1.830000e+02 1.776800e+02 +13 7094 -1.459800e+03 7.077800e+02 +2 7095 -1.780000e+02 1.939700e+02 +13 7095 -1.434760e+03 7.473400e+02 +2 7096 -1.959400e+02 1.954500e+02 +13 7096 -1.492270e+03 7.538000e+02 +2 7097 -1.827400e+02 1.996100e+02 +13 7097 -1.447800e+03 7.628500e+02 +2 7098 -2.109300e+02 2.074500e+02 +13 7098 -1.538100e+03 7.841100e+02 +2 7099 -2.337100e+02 2.211800e+02 +13 7099 -1.622370e+03 8.213000e+02 +2 7100 6.924000e+02 2.801800e+02 +17 7100 -1.077990e+03 7.572200e+02 +2 7101 7.081100e+02 2.805500e+02 +17 7101 -1.053960e+03 7.569299e+02 +2 7102 7.159600e+02 2.811500e+02 +17 7102 -1.042200e+03 7.575200e+02 +2 7103 7.159600e+02 2.811500e+02 +17 7103 -1.042200e+03 7.575200e+02 +2 7104 7.808400e+02 3.025400e+02 +17 7104 -9.313100e+02 7.855800e+02 +2 7105 7.756100e+02 3.026600e+02 +17 7105 -9.393600e+02 7.859000e+02 +2 7106 7.008600e+02 4.271700e+02 +17 7106 -1.091790e+03 9.853999e+02 +3 7107 7.983300e+02 1.191200e+02 +17 7107 -1.147890e+03 3.829800e+02 +3 7108 9.034200e+02 3.188500e+02 +17 7108 -1.067890e+03 5.284099e+02 +3 7109 -2.910300e+02 6.735999e+01 +13 7109 -9.770500e+02 5.546500e+02 +3 7110 3.844700e+02 -2.473600e+02 +17 7110 -1.547150e+03 1.098600e+02 +3 7111 4.030300e+02 -2.267900e+02 +17 7111 -1.524280e+03 1.367000e+02 +3 7112 1.102150e+03 1.910300e+02 +17 7112 -9.092000e+02 4.029600e+02 +3 7113 -5.420100e+02 2.552200e+02 +13 7113 -1.354030e+03 5.766599e+02 +3 7114 -9.037900e+02 3.045500e+02 +20 7114 -4.015100e+02 -1.891899e+02 +3 7115 -6.605000e+02 -2.745200e+02 +13 7115 -1.510430e+03 -2.357600e+02 +3 7116 4.123199e+02 -7.158002e+01 +17 7116 -1.508620e+03 3.020400e+02 +3 7117 4.123199e+02 -7.158002e+01 +17 7117 -1.511630e+03 3.055701e+02 +3 7118 -8.661400e+02 4.687900e+02 +12 7118 -8.539500e+02 -4.494900e+02 +3 7119 -1.988600e+02 -2.332100e+02 +10 7119 -1.089966e+00 -4.605900e+02 +13 7119 -7.309400e+02 8.169995e+01 +18 7119 -2.806200e+02 -3.449951e+00 +20 7119 -2.394399e+02 -1.990800e+02 +3 7120 -7.441700e+02 -2.306300e+02 +13 7120 -1.609340e+03 -1.826600e+02 +3 7121 -2.249600e+02 -2.278300e+02 +10 7121 -1.607996e+01 -4.592700e+02 +13 7121 -7.985200e+02 9.083997e+01 +18 7121 -2.946899e+02 -2.510010e+00 +3 7122 4.184800e+02 -2.180200e+02 +17 7122 -1.505190e+03 1.421300e+02 +3 7123 4.250000e+02 -5.083002e+01 +17 7123 -1.496340e+03 3.250300e+02 +3 7124 1.036410e+03 1.044000e+01 +17 7124 -9.634500e+02 2.549199e+02 +3 7125 -4.967900e+02 2.113201e+02 +13 7125 -1.296870e+03 5.292800e+02 +3 7126 -4.967900e+02 2.113201e+02 +13 7126 -1.296870e+03 5.292800e+02 +18 7126 -3.856000e+02 3.165002e+01 +3 7127 1.021700e+03 2.322500e+02 +17 7127 -9.732000e+02 4.426799e+02 +3 7128 8.930200e+02 3.505100e+02 +17 7128 -1.074190e+03 5.592200e+02 +3 7129 -6.988300e+02 -2.662100e+02 +13 7129 -1.557120e+03 -2.269399e+02 +3 7130 -3.040500e+02 -1.274900e+02 +13 7130 -1.006200e+03 1.123101e+02 +18 7130 -3.318700e+02 -3.617004e+01 +20 7130 -2.806200e+02 -2.277200e+02 +3 7131 3.162800e+02 -8.554999e+01 +17 7131 -1.633810e+03 3.378800e+02 +3 7132 1.046500e+03 2.010999e+01 +17 7132 -9.569200e+02 2.625601e+02 +3 7133 -8.097100e+02 3.743600e+02 +13 7133 -1.673860e+03 6.181000e+02 +3 7134 7.052100e+02 5.799600e+02 +12 7134 -2.172400e+02 -2.886000e+02 +3 7135 -2.862400e+02 -2.454200e+02 +20 7135 -2.755300e+02 -2.633000e+02 +3 7136 -2.290000e+02 -2.178500e+02 +10 7136 -1.875000e+01 -4.535800e+02 +13 7136 -8.093100e+02 1.160100e+02 +16 7136 8.667300e+02 2.956600e+02 +18 7136 -2.971801e+02 2.560059e+00 +20 7136 -2.534301e+02 -1.940500e+02 +3 7137 -6.744300e+02 -2.179399e+02 +13 7137 -1.534490e+03 -1.540900e+02 +3 7138 -3.392004e+01 -7.750000e+01 +10 7138 1.127300e+02 -3.408900e+02 +11 7138 6.878500e+02 3.277200e+02 +12 7138 -3.477900e+02 -3.632200e+02 +3 7139 -8.142100e+02 -4.591998e+01 +13 7139 -1.684720e+03 5.481995e+01 +3 7140 4.362000e+02 -2.453998e+01 +17 7140 -1.484340e+03 3.541899e+02 +3 7141 1.050030e+03 3.700000e+01 +17 7141 -9.526600e+02 2.758700e+02 +3 7142 4.124100e+02 9.369000e+01 +17 7142 -1.512310e+03 5.497300e+02 +3 7143 6.244399e+02 2.302600e+02 +17 7143 -1.294720e+03 5.338201e+02 +3 7144 -5.891000e+02 2.458700e+02 +13 7144 -1.415090e+03 5.287800e+02 +3 7145 -7.812100e+02 3.899000e+02 +13 7145 -1.643850e+03 6.528700e+02 +3 7146 -7.548600e+02 -3.521000e+02 +13 7146 -1.623320e+03 -3.464800e+02 +3 7147 4.266899e+02 -3.033800e+02 +17 7147 -1.496230e+03 4.747998e+01 +3 7148 -7.109700e+02 -2.570900e+02 +13 7148 -1.573980e+03 -2.144100e+02 +3 7149 -2.304800e+02 -2.361200e+02 +10 7149 -1.957996e+01 -4.636100e+02 +13 7149 -8.142900e+02 6.912000e+01 +16 7149 8.652800e+02 2.876700e+02 +3 7150 -2.228800e+02 -2.138700e+02 +13 7150 -7.941800e+02 1.293301e+02 +18 7150 -2.941000e+02 5.739990e+00 +3 7151 -2.777100e+02 -1.829100e+02 +13 7151 -9.574100e+02 2.414001e+01 +3 7152 4.994900e+02 -1.343900e+02 +17 7152 -1.415420e+03 2.187700e+02 +3 7153 -5.530300e+02 -1.162600e+02 +13 7153 -1.376970e+03 1.165002e+01 +3 7154 -4.126000e+02 -5.799988e+00 +13 7154 -1.181720e+03 2.357300e+02 +3 7155 -3.191900e+02 2.267999e+01 +13 7155 -1.027060e+03 4.034199e+02 +3 7156 4.972500e+02 1.431600e+02 +17 7156 -1.415540e+03 5.155400e+02 +3 7157 -5.170900e+02 2.399600e+02 +13 7157 -1.325540e+03 5.700000e+02 +3 7158 9.094700e+02 3.025400e+02 +17 7158 -1.062790e+03 5.137000e+02 +3 7159 -7.338700e+02 -3.560100e+02 +13 7159 -1.598820e+03 -3.515900e+02 +3 7160 -7.338700e+02 -3.560100e+02 +13 7160 -1.598820e+03 -3.515900e+02 +3 7161 -7.414900e+02 -3.510500e+02 +13 7161 -1.607840e+03 -3.451700e+02 +3 7162 -7.414900e+02 -3.510500e+02 +13 7162 -1.607840e+03 -3.451700e+02 +3 7163 -7.296900e+02 -2.364700e+02 +13 7163 -1.592440e+03 -1.896801e+02 +3 7164 -7.248900e+02 -2.348800e+02 +13 7164 -1.586730e+03 -1.861400e+02 +3 7165 4.006700e+02 -2.209000e+02 +17 7165 -1.525970e+03 1.440000e+02 +3 7166 -7.474100e+02 -2.118000e+02 +13 7166 -1.612330e+03 -1.571801e+02 +3 7167 -8.123800e+02 -2.068700e+02 +13 7167 -1.685060e+03 -1.574500e+02 +3 7168 -3.070600e+02 -1.140000e+02 +13 7168 -1.011640e+03 1.309299e+02 +3 7169 -4.646900e+02 -8.509003e+01 +13 7169 -1.259470e+03 8.794995e+01 +3 7170 9.819500e+02 -7.464001e+01 +17 7170 -1.006250e+03 1.876000e+02 +3 7171 -4.157000e+02 -1.419983e+00 +13 7171 -1.185660e+03 2.414399e+02 +3 7172 4.860400e+02 3.699951e-01 +17 7172 -1.428280e+03 3.684900e+02 +3 7173 1.093510e+03 2.976001e+01 +17 7173 -9.190400e+02 2.674199e+02 +3 7174 -7.820400e+02 1.133400e+02 +13 7174 -1.647080e+03 2.752100e+02 +3 7175 -3.012000e+02 1.315100e+02 +13 7175 -9.904900e+02 6.807900e+02 +3 7176 -7.094500e+02 1.350200e+02 +13 7176 -1.565930e+03 3.298500e+02 +3 7177 -4.595100e+02 1.455800e+02 +13 7177 -1.248790e+03 4.623500e+02 +3 7178 -7.558000e+02 1.493000e+02 +13 7178 -1.618170e+03 3.333101e+02 +3 7179 -7.590500e+02 1.524500e+02 +13 7179 -1.622360e+03 3.386899e+02 +3 7180 -3.971200e+02 1.575300e+02 +13 7180 -1.156030e+03 5.348900e+02 +3 7181 -3.971200e+02 1.575300e+02 +13 7181 -1.156030e+03 5.348900e+02 +3 7182 -6.738000e+02 2.713900e+02 +13 7182 -1.524130e+03 5.380701e+02 +3 7183 -4.880800e+02 3.163600e+02 +13 7183 -1.283820e+03 7.090500e+02 +3 7184 -5.947200e+02 3.503101e+02 +13 7184 -1.420860e+03 6.757600e+02 +3 7185 -5.746600e+02 4.014600e+02 +13 7185 -1.392130e+03 7.556799e+02 +3 7186 1.021940e+03 4.358000e+02 +17 7186 -9.711700e+02 6.151400e+02 +3 7187 -7.030400e+02 5.260701e+02 +13 7187 -1.553020e+03 8.770500e+02 +3 7188 -8.299100e+02 5.605900e+02 +13 7188 -1.682090e+03 8.389000e+02 +3 7189 7.018800e+02 6.083900e+02 +17 7189 -1.193400e+03 9.952600e+02 +3 7190 6.162200e+02 6.405200e+02 +17 7190 -1.286100e+03 1.034880e+03 +3 7191 -5.293400e+02 -9.678998e+01 +13 7191 -1.346780e+03 4.575000e+01 +3 7192 -3.184500e+02 -9.079999e+01 +13 7192 -1.033440e+03 1.781899e+02 +3 7193 -4.681600e+02 -8.721002e+01 +13 7193 -1.264820e+03 8.365002e+01 +3 7194 -3.456600e+02 -4.095001e+01 +13 7194 -1.078080e+03 2.364800e+02 +3 7195 -6.481900e+02 -6.199951e-01 +13 7195 -1.493110e+03 1.527800e+02 +3 7196 -4.834800e+02 1.392300e+02 +13 7196 -1.283220e+03 4.341200e+02 +3 7197 -5.131500e+02 1.695400e+02 +13 7197 -1.320790e+03 4.623000e+02 +3 7198 -3.909900e+02 1.720600e+02 +13 7198 -1.145370e+03 5.659900e+02 +3 7199 6.176801e+02 2.196300e+02 +17 7199 -1.300490e+03 5.234700e+02 +3 7200 -5.700500e+02 4.087700e+02 +13 7200 -1.384970e+03 7.658000e+02 +3 7201 5.462800e+02 4.653101e+02 +17 7201 -1.362770e+03 8.473000e+02 +3 7202 5.462800e+02 4.653101e+02 +17 7202 -1.362770e+03 8.473000e+02 +3 7203 -7.666400e+02 5.258500e+02 +13 7203 -1.617130e+03 8.247800e+02 +3 7204 -6.910100e+02 5.814900e+02 +13 7204 -1.590470e+03 1.114130e+03 +3 7205 6.972700e+02 5.981100e+02 +17 7205 -1.198460e+03 9.841799e+02 +3 7206 5.811200e+02 6.291200e+02 +17 7206 -1.322400e+03 1.041480e+03 +3 7207 -7.823700e+02 -2.195200e+02 +13 7207 -1.651850e+03 -1.716300e+02 +3 7208 4.583500e+02 -1.879000e+02 +17 7208 -1.459510e+03 1.693101e+02 +3 7209 7.513101e+02 -1.844100e+02 +17 7209 -1.191230e+03 1.116400e+02 +3 7210 -3.099600e+02 -5.448999e+01 +13 7210 -1.013300e+03 2.510601e+02 +3 7211 -4.614800e+02 3.183002e+01 +13 7211 -1.253630e+03 2.786300e+02 +3 7212 3.325800e+02 4.223999e+01 +17 7212 -1.616470e+03 4.906200e+02 +3 7213 -3.251600e+02 1.194800e+02 +13 7213 -1.038010e+03 6.575701e+02 +3 7214 -3.078700e+02 1.278100e+02 +13 7214 -1.006470e+03 6.731899e+02 +3 7215 4.782400e+02 1.290200e+02 +17 7215 -1.436300e+03 5.093700e+02 +3 7216 -7.463600e+02 1.382100e+02 +13 7216 -1.604500e+03 3.174500e+02 +3 7217 9.673999e+02 1.537700e+02 +17 7217 -1.016500e+03 3.817000e+02 +3 7218 -3.238700e+02 1.600000e+02 +13 7218 -1.035010e+03 7.411300e+02 +3 7219 -4.893000e+02 2.015701e+02 +13 7219 -1.284960e+03 5.140901e+02 +3 7220 -4.928000e+02 2.924600e+02 +13 7220 -1.291760e+03 6.727000e+02 +3 7221 5.004900e+02 4.197700e+02 +17 7221 -1.409560e+03 8.370100e+02 +3 7222 -6.867400e+02 5.841400e+02 +13 7222 -1.583190e+03 1.118330e+03 +4 7223 -1.073740e+03 5.587100e+02 +15 7223 -3.910800e+02 4.450100e+02 +4 7224 -2.826899e+02 6.286600e+02 +15 7224 4.229000e+02 5.255800e+02 +4 7225 -1.381790e+03 5.816500e+02 +15 7225 -6.877600e+02 4.657900e+02 +4 7226 -9.675000e+01 6.398900e+02 +15 7226 6.414800e+02 5.504399e+02 +4 7227 -1.161520e+03 5.439900e+02 +15 7227 -4.753500e+02 4.289900e+02 +4 7228 -1.306650e+03 6.174700e+02 +15 7228 -6.144900e+02 5.027200e+02 +4 7229 -1.306650e+03 6.174700e+02 +15 7229 -6.144900e+02 5.027200e+02 +4 7230 1.277910e+03 2.589600e+02 +16 7230 6.967200e+02 2.841100e+02 +4 7231 1.240760e+03 2.685100e+02 +16 7231 6.751300e+02 2.910300e+02 +4 7232 -5.565002e+01 3.372100e+02 +15 7232 6.868800e+02 2.015400e+02 +16 7232 -5.132000e+02 3.559000e+02 +4 7233 -1.051840e+03 4.641000e+02 +15 7233 -3.712700e+02 3.428400e+02 +4 7234 -1.051840e+03 4.641000e+02 +15 7234 -3.712700e+02 3.428400e+02 +4 7235 -1.084540e+03 4.660801e+02 +15 7235 -4.036100e+02 3.468201e+02 +4 7236 -1.301140e+03 4.766899e+02 +15 7236 -6.144200e+02 3.569800e+02 +4 7237 1.329500e+02 5.241300e+02 +14 7237 1.241000e+01 4.188101e+02 +4 7238 2.063000e+01 5.391200e+02 +15 7238 7.779500e+02 4.314500e+02 +4 7239 -1.124620e+03 5.453500e+02 +15 7239 -4.409700e+02 4.294900e+02 +4 7240 -1.124620e+03 5.453500e+02 +15 7240 -4.409700e+02 4.294900e+02 +4 7241 -8.101800e+02 5.886200e+02 +15 7241 -1.678900e+02 4.672300e+02 +4 7242 -7.390200e+02 5.980000e+02 +15 7242 -8.741998e+01 4.788600e+02 +4 7243 -1.127230e+03 6.034200e+02 +15 7243 -4.406600e+02 4.888900e+02 +4 7244 -1.127230e+03 6.034200e+02 +15 7244 -4.406600e+02 4.888900e+02 +4 7245 -1.196750e+03 6.036899e+02 +15 7245 -5.083300e+02 4.904800e+02 +4 7246 -1.270130e+03 6.078800e+02 +15 7246 -5.787700e+02 4.944700e+02 +4 7247 -1.342960e+03 6.132800e+02 +15 7247 -6.502400e+02 5.003000e+02 +4 7248 -8.438000e+02 6.465701e+02 +15 7248 -2.059100e+02 5.234700e+02 +4 7249 -1.275400e+02 7.193101e+02 +15 7249 5.957800e+02 6.285500e+02 +4 7250 1.364200e+02 4.987400e+02 +16 7250 -3.262300e+02 5.274200e+02 +4 7251 -1.102650e+03 5.073700e+02 +15 7251 -4.200400e+02 3.905800e+02 +4 7252 -3.226000e+02 5.313201e+02 +15 7252 3.778101e+02 4.156200e+02 +16 7252 -8.297200e+02 5.730601e+02 +19 7252 -1.141700e+02 6.536400e+02 +4 7253 -1.099760e+03 5.392300e+02 +15 7253 -4.155700e+02 4.228800e+02 +4 7254 -9.964600e+02 5.431300e+02 +15 7254 -3.186800e+02 4.264000e+02 +4 7255 -7.885500e+02 5.652600e+02 +15 7255 -1.407600e+02 4.409500e+02 +4 7256 -1.126130e+03 5.736100e+02 +15 7256 -4.397200e+02 4.589700e+02 +4 7257 -1.162690e+03 6.434399e+02 +15 7257 -4.726900e+02 5.303400e+02 +4 7258 -1.130900e+02 2.621400e+02 +15 7258 6.183199e+02 1.158000e+02 +4 7259 -2.984000e+02 2.664199e+02 +19 7259 -7.747998e+01 1.633800e+02 +4 7260 -3.353003e+01 2.796899e+02 +14 7260 -1.169000e+02 2.259300e+02 +16 7260 -4.877000e+02 2.931799e+02 +4 7261 -3.353003e+01 2.796899e+02 +14 7261 -1.169000e+02 2.259300e+02 +16 7261 -4.877000e+02 2.931799e+02 +4 7262 1.302650e+03 3.003600e+02 +16 7262 7.114100e+02 3.250800e+02 +4 7263 -1.771997e+01 3.897200e+02 +16 7263 -5.595900e+02 4.166899e+02 +4 7264 4.318300e+02 4.596100e+02 +19 7264 1.207560e+03 4.654600e+02 +4 7265 -1.027510e+03 4.645300e+02 +15 7265 -3.448500e+02 3.449200e+02 +4 7266 -9.785999e+01 4.672700e+02 +10 7266 -1.317520e+03 -1.396600e+02 +15 7266 6.392400e+02 3.480100e+02 +16 7266 -5.624400e+02 4.969500e+02 +4 7267 -1.080850e+03 4.880900e+02 +15 7267 -3.982400e+02 3.697900e+02 +4 7268 -1.080850e+03 4.880900e+02 +15 7268 -3.982400e+02 3.697900e+02 +4 7269 -1.232510e+03 4.960500e+02 +15 7269 -5.471600e+02 3.767600e+02 +4 7270 -1.789001e+01 5.375601e+02 +19 7270 4.465900e+02 6.806899e+02 +4 7271 -9.713000e+01 5.389200e+02 +15 7271 6.404600e+02 4.289200e+02 +4 7272 -1.017520e+03 5.531600e+02 +15 7272 -3.369400e+02 4.372400e+02 +4 7273 -4.528400e+02 5.591300e+02 +15 7273 2.300699e+02 4.453600e+02 +19 7273 -3.468700e+02 6.890500e+02 +4 7274 -8.208000e+02 5.683201e+02 +19 7274 -9.513600e+02 6.567000e+02 +4 7275 -8.208000e+02 5.683201e+02 +15 7275 -1.730800e+02 4.443700e+02 +4 7276 1.937000e+01 5.896400e+02 +14 7276 -6.395999e+01 4.898900e+02 +15 7276 7.728800e+02 4.880800e+02 +19 7276 5.187800e+02 7.759399e+02 +4 7277 1.937000e+01 5.896400e+02 +19 7277 5.187800e+02 7.759399e+02 +4 7278 -3.317004e+01 6.004399e+02 +15 7278 7.123700e+02 5.000200e+02 +16 7278 -4.983100e+02 6.432600e+02 +4 7279 -3.317004e+01 6.004399e+02 +15 7279 7.123700e+02 5.000200e+02 +4 7280 -1.103380e+03 6.056100e+02 +15 7280 -4.170800e+02 4.944299e+02 +4 7281 -1.467680e+03 6.215500e+02 +15 7281 -7.648800e+02 5.031600e+02 +4 7282 -1.467680e+03 6.215500e+02 +15 7282 -7.648800e+02 5.031600e+02 +4 7283 -1.468680e+03 6.416100e+02 +15 7283 -7.651700e+02 5.221500e+02 +4 7284 5.757996e+01 2.214600e+02 +15 7284 8.128400e+02 6.771002e+01 +4 7285 1.292750e+03 2.279600e+02 +16 7285 7.080699e+02 2.610000e+02 +4 7286 -3.008300e+02 2.495400e+02 +19 7286 -8.318005e+01 1.315901e+02 +4 7287 1.191110e+03 2.996200e+02 +16 7287 6.433800e+02 3.259800e+02 +4 7288 -1.996500e+02 3.355000e+02 +15 7288 5.192600e+02 2.011500e+02 +16 7288 -6.743900e+02 3.531300e+02 +4 7289 8.489001e+01 4.129700e+02 +14 7289 -1.909000e+01 3.335300e+02 +15 7289 8.444399e+02 2.903900e+02 +4 7290 8.489001e+01 4.129700e+02 +19 7290 6.404299e+02 4.424900e+02 +4 7291 -9.760000e+02 4.692100e+02 +15 7291 -2.924600e+02 3.502000e+02 +4 7292 4.303400e+02 4.940400e+02 +19 7292 1.207200e+03 5.240100e+02 +4 7293 -1.000660e+03 5.288300e+02 +15 7293 -3.244400e+02 4.125800e+02 +4 7294 -1.000660e+03 5.288300e+02 +15 7294 -3.244400e+02 4.125800e+02 +4 7295 -1.827400e+02 5.343400e+02 +15 7295 5.083400e+02 4.203500e+02 +4 7296 -4.280601e+02 5.449500e+02 +19 7296 -3.046100e+02 6.657700e+02 +4 7297 5.112000e+01 5.499500e+02 +14 7297 -4.054001e+01 4.516799e+02 +15 7297 8.078101e+02 4.432500e+02 +16 7297 -4.086100e+02 5.837600e+02 +19 7297 5.782700e+02 6.987900e+02 +4 7298 -1.138300e+02 5.493000e+02 +14 7298 -1.784000e+02 4.712500e+02 +15 7298 6.211500e+02 4.405900e+02 +16 7298 -5.849800e+02 5.885100e+02 +20 7298 -1.309720e+03 9.495996e+01 +4 7299 -1.138300e+02 5.493000e+02 +15 7299 6.211500e+02 4.405900e+02 +16 7299 -5.849800e+02 5.885100e+02 +4 7300 -1.690000e+02 5.477400e+02 +15 7300 5.574500e+02 4.383600e+02 +4 7301 -9.860500e+02 5.618800e+02 +15 7301 -3.097800e+02 4.448201e+02 +4 7302 -9.860500e+02 5.618800e+02 +15 7302 -3.097800e+02 4.448201e+02 +4 7303 -4.044900e+02 5.621899e+02 +15 7303 2.837000e+02 4.493101e+02 +16 7303 -9.346800e+02 6.092000e+02 +19 7303 -2.637700e+02 6.986000e+02 +4 7304 -3.552300e+02 5.655300e+02 +14 7304 -4.075500e+02 4.955701e+02 +15 7304 3.416801e+02 4.542800e+02 +16 7304 -8.755500e+02 6.113700e+02 +19 7304 -1.753700e+02 7.101300e+02 +4 7305 -3.355000e+02 5.664900e+02 +14 7305 -3.870500e+02 4.956500e+02 +15 7305 3.643700e+02 4.559399e+02 +16 7305 -8.484500e+02 6.119200e+02 +19 7305 -1.397000e+02 7.132700e+02 +4 7306 -2.005400e+02 5.741799e+02 +14 7306 -2.576100e+02 4.959800e+02 +15 7306 5.205100e+02 4.677300e+02 +16 7306 -6.856000e+02 6.172400e+02 +19 7306 1.081200e+02 7.419200e+02 +4 7307 -1.001710e+03 5.769399e+02 +15 7307 -3.228400e+02 4.589200e+02 +4 7308 -4.813400e+02 5.807900e+02 +15 7308 1.997100e+02 4.660200e+02 +4 7309 -8.110500e+02 5.825601e+02 +15 7309 -1.647500e+02 4.590601e+02 +19 7309 -9.323800e+02 6.802000e+02 +4 7310 -3.437700e+02 5.888300e+02 +14 7310 -3.961100e+02 5.166300e+02 +15 7310 3.540100e+02 4.791200e+02 +16 7310 -8.630300e+02 6.384200e+02 +19 7310 -1.536000e+02 7.536300e+02 +4 7311 -3.104399e+02 5.966600e+02 +14 7311 -3.634400e+02 5.207300e+02 +15 7311 3.891600e+02 4.868500e+02 +16 7311 -8.222900e+02 6.457800e+02 +4 7312 -3.627600e+02 6.005601e+02 +15 7312 3.319200e+02 4.917600e+02 +16 7312 -8.907800e+02 6.513199e+02 +4 7313 -2.932900e+02 6.053900e+02 +15 7313 4.103000e+02 4.998700e+02 +16 7313 -8.046000e+02 6.549100e+02 +4 7314 -8.036700e+02 6.080900e+02 +15 7314 -1.566200e+02 4.830500e+02 +4 7315 -1.403320e+03 6.229800e+02 +15 7315 -7.055600e+02 5.045800e+02 +4 7316 -6.313600e+02 6.396100e+02 +15 7316 3.390002e+01 5.249100e+02 +4 7317 -1.270750e+03 6.498900e+02 +15 7317 -5.780100e+02 5.355500e+02 +4 7318 -1.975400e+02 6.573101e+02 +7 7318 -1.213590e+03 8.989600e+02 +10 7318 -1.569490e+03 1.679000e+02 +14 7318 -2.531500e+02 5.706300e+02 +15 7318 5.246400e+02 5.592900e+02 +16 7318 -6.868200e+02 7.103400e+02 +19 7318 1.136100e+02 8.944600e+02 +20 7318 -1.412980e+03 2.282300e+02 +4 7319 -1.434020e+03 6.795800e+02 +15 7319 -7.307800e+02 5.610300e+02 +4 7320 -3.960999e+01 2.212400e+02 +15 7320 7.021300e+02 6.915002e+01 +4 7321 -3.518005e+01 2.492900e+02 +14 7321 -1.181900e+02 1.968000e+02 +4 7322 -2.188101e+02 2.757100e+02 +14 7322 -2.839900e+02 2.285300e+02 +16 7322 -6.950000e+02 2.845100e+02 +4 7323 1.082200e+02 3.023500e+02 +15 7323 8.683000e+02 1.603700e+02 +4 7324 -1.866899e+02 3.380200e+02 +16 7324 -6.588100e+02 3.541000e+02 +4 7325 1.995996e+01 4.433301e+02 +14 7325 -6.767999e+01 3.638700e+02 +16 7325 -4.365100e+02 4.697500e+02 +4 7326 -1.109620e+03 4.451100e+02 +15 7326 -4.285900e+02 3.238500e+02 +4 7327 -1.099080e+03 4.592000e+02 +15 7327 -4.195000e+02 3.382500e+02 +4 7328 8.613000e+01 4.609299e+02 +16 7328 -3.717700e+02 4.892700e+02 +4 7329 -8.181006e+01 4.656200e+02 +16 7329 -3.955500e+02 4.868400e+02 +4 7330 -1.130300e+02 4.659199e+02 +10 7330 -1.452170e+03 -1.239100e+02 +4 7331 -1.135000e+02 4.934299e+02 +15 7331 6.211700e+02 3.780200e+02 +4 7332 -9.869600e+02 5.285701e+02 +15 7332 -3.115900e+02 4.113900e+02 +4 7333 -9.869600e+02 5.285701e+02 +15 7333 -3.115900e+02 4.113900e+02 +4 7334 -3.323999e+01 5.510200e+02 +14 7334 -1.087400e+02 4.638201e+02 +4 7335 -3.092700e+02 5.541300e+02 +14 7335 -3.626300e+02 4.825300e+02 +15 7335 3.943700e+02 4.421300e+02 +16 7335 -8.191100e+02 5.954200e+02 +19 7335 -9.384998e+01 6.926200e+02 +4 7336 -6.256900e+02 5.700000e+02 +15 7336 3.951001e+01 4.517000e+02 +4 7337 -1.014820e+03 5.700300e+02 +15 7337 -3.352600e+02 4.525100e+02 +4 7338 -4.370100e+02 5.824500e+02 +15 7338 2.480100e+02 4.692500e+02 +4 7339 -8.250900e+02 5.906400e+02 +19 7339 -9.571700e+02 6.962200e+02 +4 7340 -2.193101e+02 5.963000e+02 +15 7340 4.985100e+02 4.911100e+02 +4 7341 -1.751500e+02 5.993900e+02 +5 7341 -1.081860e+03 8.705601e+02 +7 7341 -1.172590e+03 8.050800e+02 +10 7341 -1.536120e+03 7.956995e+01 +15 7341 5.500300e+02 4.955900e+02 +16 7341 -6.842000e+02 6.438101e+02 +4 7342 -8.155600e+02 6.004700e+02 +15 7342 -1.684300e+02 4.775300e+02 +4 7343 -1.403750e+03 6.013900e+02 +15 7343 -7.052800e+02 4.824100e+02 +4 7344 -3.334100e+02 6.022500e+02 +16 7344 -8.530300e+02 6.522500e+02 +4 7345 -2.086500e+02 6.092800e+02 +7 7345 -1.230380e+03 8.278900e+02 +10 7345 -1.592300e+03 1.056200e+02 +15 7345 5.106600e+02 5.063000e+02 +16 7345 -6.965300e+02 6.571899e+02 +19 7345 9.442004e+01 8.056400e+02 +20 7345 -1.431660e+03 1.798000e+02 +4 7346 -5.503700e+02 6.101100e+02 +15 7346 1.218500e+02 4.966300e+02 +4 7347 -4.069995e+01 6.124800e+02 +15 7347 6.992500e+02 5.123800e+02 +16 7347 -5.128200e+02 6.544800e+02 +4 7348 -1.962100e+02 6.155900e+02 +5 7348 -1.084480e+03 8.969800e+02 +10 7348 -1.571870e+03 1.091200e+02 +14 7348 -2.536800e+02 5.332100e+02 +15 7348 5.247600e+02 5.128600e+02 +16 7348 -6.833900e+02 6.631100e+02 +19 7348 1.159399e+02 8.181799e+02 +20 7348 -1.415410e+03 1.810100e+02 +4 7349 -6.740900e+02 6.156500e+02 +15 7349 -1.252002e+01 4.990300e+02 +4 7350 -6.740900e+02 6.156500e+02 +15 7350 -1.252002e+01 4.990300e+02 +4 7351 -2.411000e+02 6.174800e+02 +5 7351 -1.145160e+03 8.896100e+02 +7 7351 -1.288240e+03 8.423900e+02 +10 7351 -1.651120e+03 1.209700e+02 +14 7351 -2.963300e+02 5.344100e+02 +15 7351 4.736400e+02 5.137000e+02 +16 7351 -7.372100e+02 6.662200e+02 +19 7351 3.350000e+01 8.124200e+02 +20 7351 -1.476890e+03 1.902300e+02 +4 7352 -1.513900e+02 6.225000e+02 +15 7352 5.769900e+02 5.211000e+02 +4 7353 -3.306899e+02 6.264800e+02 +14 7353 -3.817300e+02 5.475699e+02 +4 7354 -2.593600e+02 6.313600e+02 +5 7354 -1.174360e+03 9.044301e+02 +10 7354 -1.682020e+03 1.442400e+02 +15 7354 4.529399e+02 5.284100e+02 +16 7354 -7.585300e+02 6.832000e+02 +4 7355 -1.445010e+03 6.486500e+02 +15 7355 -7.422200e+02 5.298900e+02 +4 7356 -1.440980e+03 6.676200e+02 +15 7356 -7.376000e+02 5.494700e+02 +4 7357 -1.415240e+03 6.710800e+02 +15 7357 -7.131600e+02 5.530000e+02 +4 7358 1.480630e+03 1.925200e+02 +16 7358 9.635000e+02 2.322900e+02 +4 7359 -3.205300e+02 2.309800e+02 +19 7359 -1.150400e+02 9.725000e+01 +4 7360 -9.554004e+01 2.343000e+02 +14 7360 -1.704400e+02 1.863200e+02 +15 7360 6.393500e+02 8.389001e+01 +16 7360 -5.520400e+02 2.416000e+02 +4 7361 -2.494600e+02 2.967800e+02 +14 7361 -3.123000e+02 2.477200e+02 +19 7361 1.266003e+01 2.222000e+02 +4 7362 6.054004e+01 3.045801e+02 +10 7362 -1.232090e+03 -3.774700e+02 +14 7362 -4.023999e+01 2.398400e+02 +15 7362 8.163300e+02 1.634900e+02 +4 7363 -2.594800e+02 3.049299e+02 +19 7363 -6.260010e+00 2.362100e+02 +4 7364 -2.149200e+02 3.064900e+02 +14 7364 -2.765600e+02 2.558500e+02 +4 7365 -2.472600e+02 3.135300e+02 +14 7365 -3.094600e+02 2.627400e+02 +15 7365 4.632300e+02 1.751100e+02 +19 7365 9.020020e+00 2.536899e+02 +4 7366 -2.120800e+02 3.292000e+02 +19 7366 8.338000e+01 2.860901e+02 +4 7367 -1.766100e+02 3.322600e+02 +15 7367 5.462600e+02 1.951500e+02 +16 7367 -6.479100e+02 3.478500e+02 +4 7368 7.894900e+02 3.593000e+02 +16 7368 3.404000e+02 3.829100e+02 +4 7369 -2.000000e+02 3.832100e+02 +16 7369 -6.758800e+02 4.046799e+02 +4 7370 2.693101e+02 4.244399e+02 +15 7370 9.776200e+02 2.946300e+02 +19 7370 8.803401e+02 3.684199e+02 +4 7371 2.841801e+02 4.284199e+02 +16 7371 -2.041200e+02 4.547500e+02 +19 7371 9.720701e+02 4.021699e+02 +4 7372 4.258300e+02 4.350500e+02 +16 7372 -7.081000e+01 4.561400e+02 +4 7373 1.065000e+02 4.726599e+02 +16 7373 -3.535800e+02 5.010701e+02 +4 7374 1.065000e+02 4.726599e+02 +16 7374 -4.060900e+02 5.082000e+02 +4 7375 -3.787500e+02 4.933201e+02 +15 7375 3.145400e+02 3.737800e+02 +16 7375 -9.008700e+02 5.286899e+02 +4 7376 -1.103460e+03 5.185800e+02 +15 7376 -4.220800e+02 4.005900e+02 +4 7377 -1.013290e+03 5.366300e+02 +15 7377 -3.354000e+02 4.201799e+02 +4 7378 5.099976e+00 5.579800e+02 +10 7378 -1.277680e+03 -1.333997e+01 +14 7378 -7.672000e+01 4.647000e+02 +15 7378 7.565900e+02 4.516700e+02 +16 7378 -4.557700e+02 5.945100e+02 +20 7378 -1.188180e+03 9.146997e+01 +4 7379 -6.338300e+02 5.612800e+02 +15 7379 3.067004e+01 4.427400e+02 +4 7380 -6.338300e+02 5.612800e+02 +15 7380 3.067004e+01 4.427400e+02 +4 7381 -1.014900e+03 5.700200e+02 +15 7381 -3.352600e+02 4.525100e+02 +4 7382 -4.488400e+02 5.767400e+02 +15 7382 2.356400e+02 4.643101e+02 +19 7382 -3.402600e+02 7.179600e+02 +4 7383 -6.536100e+02 5.786400e+02 +15 7383 8.329956e+00 4.603000e+02 +4 7384 -4.255200e+02 5.795601e+02 +15 7384 2.618800e+02 4.668800e+02 +19 7384 -2.986700e+02 7.245100e+02 +4 7385 -3.559600e+02 5.824200e+02 +14 7385 -4.069800e+02 5.098000e+02 +15 7385 3.405500e+02 4.714500e+02 +16 7385 -8.764300e+02 6.299200e+02 +19 7385 -1.752800e+02 7.375900e+02 +4 7386 -1.024200e+03 5.918700e+02 +15 7386 -3.427100e+02 4.791000e+02 +4 7387 -8.380800e+02 6.039399e+02 +19 7387 -9.757100e+02 7.150701e+02 +4 7388 -1.078580e+03 6.236200e+02 +15 7388 -3.919900e+02 5.126500e+02 +4 7389 -1.090040e+03 6.242300e+02 +15 7389 -4.030100e+02 5.128400e+02 +4 7390 -1.119820e+03 6.258201e+02 +15 7390 -4.327200e+02 5.140100e+02 +4 7391 -1.134770e+03 6.269200e+02 +15 7391 -4.479300e+02 5.152300e+02 +4 7392 -2.308800e+02 6.277000e+02 +5 7392 -1.134370e+03 9.071200e+02 +7 7392 -1.267790e+03 8.561799e+02 +10 7392 -1.628220e+03 1.315200e+02 +14 7392 -2.850700e+02 5.447200e+02 +15 7392 4.858400e+02 5.248101e+02 +16 7392 -7.235200e+02 6.781400e+02 +19 7392 5.379004e+01 8.368800e+02 +20 7392 -1.460000e+03 1.990500e+02 +4 7393 -1.150150e+03 6.280200e+02 +15 7393 -4.640500e+02 5.159800e+02 +4 7394 -2.184900e+02 6.292200e+02 +10 7394 -1.609110e+03 1.264000e+02 +16 7394 -7.097700e+02 6.775000e+02 +19 7394 7.612000e+01 8.399800e+02 +4 7395 -1.391130e+03 6.456000e+02 +15 7395 -6.929200e+02 5.279000e+02 +4 7396 -1.438410e+03 6.573900e+02 +15 7396 -7.361400e+02 5.390800e+02 +4 7397 -1.438410e+03 6.573900e+02 +15 7397 -7.361400e+02 5.390800e+02 +4 7398 -6.520996e+01 6.757000e+02 +19 7398 3.603000e+02 9.104200e+02 +4 7399 -1.406800e+03 6.774100e+02 +15 7399 -7.040300e+02 5.596100e+02 +4 7400 -1.758800e+02 2.571200e+02 +14 7400 -2.431400e+02 2.092300e+02 +16 7400 -6.440100e+02 2.649299e+02 +4 7401 -2.864100e+02 2.676599e+02 +19 7401 -5.597998e+01 1.655100e+02 +4 7402 -1.742400e+02 3.155500e+02 +16 7402 -6.453600e+02 3.298000e+02 +4 7403 -7.752002e+01 3.273401e+02 +19 7403 3.371899e+02 2.844900e+02 +4 7404 -2.420800e+02 3.622700e+02 +16 7404 -7.276400e+02 3.805300e+02 +4 7405 1.171997e+01 3.743900e+02 +15 7405 7.634800e+02 2.432000e+02 +16 7405 -4.423100e+02 3.950100e+02 +4 7406 -2.451000e+02 3.838700e+02 +14 7406 -3.045400e+02 3.261300e+02 +15 7406 4.667600e+02 2.538600e+02 +16 7406 -7.331600e+02 4.042700e+02 +4 7407 1.504800e+02 4.261799e+02 +10 7407 -1.168370e+03 -2.006100e+02 +15 7407 9.103101e+02 3.011600e+02 +4 7408 5.609985e+00 4.501200e+02 +16 7408 -4.527100e+02 4.778800e+02 +4 7409 -1.001100e+03 4.533000e+02 +15 7409 -3.191700e+02 3.327800e+02 +4 7410 -3.229600e+02 4.650801e+02 +15 7410 3.755800e+02 3.438000e+02 +16 7410 -8.319000e+02 4.966300e+02 +19 7410 -1.198800e+02 5.292700e+02 +4 7411 -3.926801e+02 4.781799e+02 +15 7411 2.979301e+02 3.569000e+02 +16 7411 -9.166200e+02 5.113900e+02 +4 7412 2.952000e+02 4.792400e+02 +16 7412 -2.365200e+02 4.959000e+02 +4 7413 -1.287590e+03 5.043400e+02 +15 7413 -6.007400e+02 3.843101e+02 +4 7414 -1.346170e+03 5.071500e+02 +15 7414 -6.565500e+02 3.870000e+02 +4 7415 -8.044900e+02 5.295300e+02 +19 7415 -9.241200e+02 5.901300e+02 +4 7416 1.445200e+02 5.338800e+02 +15 7416 9.039000e+02 4.245800e+02 +16 7416 -3.207000e+02 5.639100e+02 +19 7416 7.407500e+02 6.514500e+02 +4 7417 -5.830005e+01 5.340800e+02 +5 7417 -8.702700e+02 8.100601e+02 +10 7417 -1.364700e+03 -3.596997e+01 +15 7417 6.833500e+02 4.243300e+02 +16 7417 -5.235300e+02 5.699800e+02 +20 7417 -1.251110e+03 7.065991e+01 +4 7418 3.771997e+01 5.361700e+02 +14 7418 -5.234000e+01 4.414600e+02 +4 7419 -8.048800e+02 5.528700e+02 +15 7419 -1.588900e+02 4.281400e+02 +19 7419 -9.225000e+02 6.265500e+02 +4 7420 -6.164800e+02 5.678300e+02 +15 7420 4.991003e+01 4.499700e+02 +4 7421 -5.961800e+02 5.809900e+02 +15 7421 7.275000e+01 4.650300e+02 +4 7422 -3.805300e+02 5.822300e+02 +14 7422 -4.312200e+02 5.097100e+02 +15 7422 3.122800e+02 4.699100e+02 +16 7422 -9.087900e+02 6.287300e+02 +19 7422 -2.201100e+02 7.325900e+02 +4 7423 -4.077700e+02 5.861600e+02 +19 7423 -2.671801e+02 7.407100e+02 +4 7424 -3.992200e+02 5.881300e+02 +14 7424 -4.484200e+02 5.180300e+02 +15 7424 2.923300e+02 4.773600e+02 +16 7424 -9.318900e+02 6.384100e+02 +19 7424 -2.537200e+02 7.443000e+02 +4 7425 -9.825800e+02 5.920800e+02 +15 7425 -3.046200e+02 4.774299e+02 +4 7426 -3.050300e+02 5.929600e+02 +15 7426 3.992000e+02 4.849200e+02 +4 7427 -1.195200e+02 5.952500e+02 +7 7427 -1.081580e+03 7.890701e+02 +10 7427 -1.447020e+03 5.991003e+01 +16 7427 -5.920700e+02 6.383600e+02 +4 7428 -3.911500e+02 5.950701e+02 +14 7428 -4.405100e+02 5.243101e+02 +15 7428 3.000000e+02 4.855900e+02 +16 7428 -9.212200e+02 6.468600e+02 +4 7429 -9.952500e+02 5.953900e+02 +15 7429 -3.175700e+02 4.814200e+02 +4 7430 -3.213700e+02 5.995100e+02 +15 7430 3.786700e+02 4.931500e+02 +4 7431 -6.227700e+02 5.986600e+02 +15 7431 4.277002e+01 4.820400e+02 +4 7432 -6.345400e+02 5.994700e+02 +15 7432 3.081995e+01 4.835800e+02 +4 7433 -1.024660e+03 6.069000e+02 +15 7433 -3.425700e+02 4.939200e+02 +4 7434 -4.791000e+02 6.081899e+02 +15 7434 2.016200e+02 4.967700e+02 +19 7434 -3.891100e+02 7.683000e+02 +4 7435 -5.596997e+01 6.157300e+02 +14 7435 -1.265000e+02 5.218400e+02 +15 7435 6.851100e+02 5.170100e+02 +20 7435 -1.246170e+03 1.599000e+02 +4 7436 -6.565400e+02 6.195400e+02 +15 7436 7.550049e+00 5.040300e+02 +4 7437 -1.108560e+03 6.247700e+02 +15 7437 -4.214900e+02 5.129100e+02 +4 7438 -2.494399e+02 6.292800e+02 +15 7438 4.631600e+02 5.257000e+02 +19 7438 1.860999e+01 8.332800e+02 +4 7439 -6.043100e+02 6.372600e+02 +15 7439 6.302002e+01 5.241700e+02 +4 7440 -1.105750e+03 6.420601e+02 +15 7440 -4.179800e+02 5.308400e+02 +4 7441 -1.176660e+03 6.467300e+02 +15 7441 -4.871800e+02 5.339299e+02 +4 7442 -2.103101e+02 6.530200e+02 +5 7442 -1.112350e+03 9.466500e+02 +7 7442 -1.235340e+03 8.941000e+02 +10 7442 -1.590630e+03 1.649099e+02 +14 7442 -2.651900e+02 5.673800e+02 +15 7442 5.094301e+02 5.539800e+02 +16 7442 -7.021400e+02 7.061200e+02 +19 7442 9.054004e+01 8.851500e+02 +20 7442 -1.430150e+03 2.255200e+02 +4 7443 -8.335800e+02 6.582400e+02 +19 7443 -9.544200e+02 7.942600e+02 +4 7444 -6.860400e+02 6.649399e+02 +15 7444 -3.679999e+01 5.462400e+02 +4 7445 -2.844900e+02 2.450200e+02 +19 7445 -5.281006e+01 1.234600e+02 +4 7446 1.219070e+03 2.556500e+02 +5 7446 8.958401e+02 6.594399e+02 +16 7446 6.608000e+02 2.840100e+02 +4 7447 -2.759301e+02 2.976200e+02 +19 7447 -3.564001e+01 2.223000e+02 +4 7448 -2.306006e+01 3.215300e+02 +15 7448 7.225100e+02 1.835600e+02 +16 7448 -4.785100e+02 3.385000e+02 +4 7449 -2.624500e+02 3.726000e+02 +19 7449 -8.979980e+00 3.621300e+02 +4 7450 -2.214301e+02 3.799099e+02 +15 7450 4.950601e+02 2.498900e+02 +4 7451 -1.571801e+02 3.924500e+02 +14 7451 -2.228200e+02 3.306200e+02 +4 7452 3.215699e+02 4.307600e+02 +14 7452 7.177002e+01 3.004800e+02 +16 7452 -1.953700e+02 4.479200e+02 +19 7452 9.860200e+02 3.915400e+02 +4 7453 1.367800e+02 4.454600e+02 +16 7453 -3.252700e+02 4.717200e+02 +4 7454 -9.640700e+02 4.515801e+02 +15 7454 -2.817100e+02 3.309800e+02 +4 7455 1.430100e+02 4.537100e+02 +15 7455 9.022300e+02 3.338000e+02 +19 7455 7.393601e+02 5.059800e+02 +4 7456 -1.027290e+03 4.791300e+02 +15 7456 -3.446500e+02 3.601500e+02 +4 7457 -9.571700e+02 4.806500e+02 +15 7457 -2.740500e+02 3.628500e+02 +4 7458 -9.380000e+02 4.944000e+02 +15 7458 -2.531200e+02 3.771600e+02 +4 7459 -1.077610e+03 4.948900e+02 +15 7459 -3.944200e+02 3.765701e+02 +4 7460 -1.086720e+03 4.956400e+02 +15 7460 -4.031900e+02 3.773400e+02 +4 7461 -1.095350e+03 4.955601e+02 +15 7461 -4.123100e+02 3.772100e+02 +4 7462 -1.114490e+03 4.967900e+02 +15 7462 -4.309500e+02 3.782500e+02 +4 7463 -1.044230e+03 4.988800e+02 +15 7463 -3.611500e+02 3.807100e+02 +4 7464 -1.158770e+03 4.986400e+02 +15 7464 -4.757300e+02 3.797000e+02 +4 7465 -1.278220e+03 4.992400e+02 +15 7465 -5.918400e+02 3.796500e+02 +4 7466 -1.061010e+03 4.998000e+02 +15 7466 -3.765300e+02 3.819800e+02 +4 7467 -1.294110e+03 5.001000e+02 +15 7467 -6.066900e+02 3.802300e+02 +4 7468 -1.216280e+03 5.011000e+02 +15 7468 -5.309100e+02 3.819100e+02 +4 7469 -1.238710e+03 5.022800e+02 +15 7469 -5.544100e+02 3.831000e+02 +4 7470 -1.354820e+03 5.027100e+02 +15 7470 -6.650300e+02 3.823600e+02 +4 7471 -1.058400e+03 5.053000e+02 +15 7471 -3.749700e+02 3.870701e+02 +4 7472 -1.065480e+03 5.049800e+02 +15 7472 -3.819600e+02 3.872600e+02 +4 7473 -1.065480e+03 5.049800e+02 +15 7473 -3.819600e+02 3.872600e+02 +4 7474 -1.306930e+03 5.055701e+02 +15 7474 -6.196200e+02 3.855601e+02 +4 7475 4.419500e+02 5.186600e+02 +16 7475 -6.221997e+01 5.374000e+02 +19 7475 1.224090e+03 5.693500e+02 +4 7476 -3.508500e+02 5.227800e+02 +19 7476 -1.671400e+02 6.331300e+02 +4 7477 -3.797400e+02 5.330000e+02 +15 7477 3.134399e+02 4.175300e+02 +4 7478 1.305000e+02 5.436700e+02 +16 7478 -3.329600e+02 5.744299e+02 +19 7478 7.177000e+02 6.755601e+02 +4 7479 -6.605800e+02 5.439900e+02 +15 7479 1.699951e+00 4.237600e+02 +4 7480 4.336300e+02 5.498600e+02 +14 7480 1.752800e+02 3.910900e+02 +16 7480 -7.259003e+01 5.705200e+02 +18 7480 -1.122780e+03 3.263201e+02 +19 7480 1.203040e+03 6.201899e+02 +20 7480 -9.639200e+02 8.084009e+01 +4 7481 -6.656400e+02 5.551000e+02 +15 7481 -3.150024e+00 4.351500e+02 +4 7482 -6.224400e+02 5.580000e+02 +15 7482 4.325000e+01 4.392500e+02 +4 7483 -6.724100e+02 5.636200e+02 +15 7483 -1.096997e+01 4.445000e+02 +4 7484 -6.724100e+02 5.636200e+02 +15 7484 -1.096997e+01 4.445000e+02 +4 7485 7.793994e+01 5.651400e+02 +20 7485 -1.127490e+03 9.309998e+01 +4 7486 -6.548900e+02 5.657500e+02 +15 7486 8.010010e+00 4.466799e+02 +4 7487 -6.548900e+02 5.657500e+02 +15 7487 8.010010e+00 4.466799e+02 +4 7488 9.598999e+01 5.715200e+02 +15 7488 8.563700e+02 4.668800e+02 +19 7488 6.591599e+02 7.339500e+02 +4 7489 -2.058600e+02 5.726899e+02 +15 7489 5.151200e+02 4.656200e+02 +4 7490 -6.115200e+02 5.736899e+02 +15 7490 5.500000e+01 4.567000e+02 +4 7491 -6.115200e+02 5.736899e+02 +15 7491 5.500000e+01 4.567000e+02 +4 7492 -4.751001e+01 5.759100e+02 +15 7492 6.983000e+02 4.718101e+02 +4 7493 -7.941900e+02 5.782500e+02 +15 7493 -1.468600e+02 4.542600e+02 +19 7493 -9.027500e+02 6.693101e+02 +4 7494 7.032996e+01 5.794100e+02 +11 7494 -9.397200e+02 6.459200e+02 +15 7494 8.269100e+02 4.762400e+02 +16 7494 -3.914100e+02 6.154900e+02 +4 7495 -2.254700e+02 5.793101e+02 +15 7495 4.923300e+02 4.719200e+02 +19 7495 6.275000e+01 7.477300e+02 +4 7496 -3.327800e+02 5.804100e+02 +15 7496 3.672600e+02 4.700400e+02 +16 7496 -8.488700e+02 6.262100e+02 +4 7497 1.239500e+02 5.805900e+02 +15 7497 8.832100e+02 4.778600e+02 +16 7497 -3.416200e+02 6.146500e+02 +19 7497 7.043201e+02 7.442200e+02 +4 7498 -5.257000e+02 5.807000e+02 +19 7498 -4.715000e+02 7.194299e+02 +4 7499 -4.692800e+02 5.834000e+02 +15 7499 2.131801e+02 4.702400e+02 +19 7499 -3.752900e+02 7.284500e+02 +4 7500 -1.111930e+03 5.858700e+02 +15 7500 -4.269700e+02 4.723101e+02 +4 7501 -1.111930e+03 5.858700e+02 +15 7501 -4.269700e+02 4.723101e+02 +4 7502 7.087000e+01 5.869800e+02 +19 7502 6.116700e+02 7.647800e+02 +4 7503 -3.098500e+02 5.882500e+02 +14 7503 -3.624000e+02 5.127500e+02 +15 7503 3.937300e+02 4.796400e+02 +19 7503 -9.234998e+01 7.542900e+02 +4 7504 -3.836600e+02 5.892500e+02 +19 7504 -2.262400e+02 7.488700e+02 +4 7505 -3.899500e+02 5.893500e+02 +15 7505 3.017800e+02 4.790200e+02 +16 7505 -9.198000e+02 6.399700e+02 +4 7506 -3.630200e+02 5.897700e+02 +15 7506 3.328101e+02 4.798700e+02 +4 7507 7.582996e+01 5.915300e+02 +15 7507 8.324301e+02 4.901700e+02 +16 7507 -3.857100e+02 6.280000e+02 +19 7507 6.218800e+02 7.736400e+02 +4 7508 4.322998e+01 5.945300e+02 +19 7508 5.609900e+02 7.824000e+02 +4 7509 8.070996e+01 5.961500e+02 +15 7509 8.383600e+02 4.955701e+02 +16 7509 -3.820400e+02 6.331300e+02 +19 7509 6.283799e+02 7.825800e+02 +4 7510 -8.282996e+01 5.981300e+02 +15 7510 6.558500e+02 4.969000e+02 +16 7510 -5.523900e+02 6.410601e+02 +4 7511 -1.922800e+02 5.992200e+02 +14 7511 -2.492100e+02 5.179500e+02 +16 7511 -6.780400e+02 6.450601e+02 +19 7511 1.235900e+02 7.882500e+02 +4 7512 -1.289001e+01 6.004500e+02 +15 7512 7.338900e+02 4.994399e+02 +19 7512 4.580800e+02 7.966000e+02 +4 7513 -1.009540e+03 6.010900e+02 +15 7513 -3.293900e+02 4.873400e+02 +4 7514 -7.958400e+02 6.018300e+02 +15 7514 -1.477300e+02 4.788400e+02 +19 7514 -9.033900e+02 7.101100e+02 +4 7515 -7.958400e+02 6.018300e+02 +15 7515 -1.477300e+02 4.788400e+02 +19 7515 -9.033900e+02 7.101100e+02 +4 7516 -5.448400e+02 6.032000e+02 +15 7516 1.272700e+02 4.894200e+02 +19 7516 -5.036300e+02 7.528500e+02 +4 7517 1.553003e+01 6.041799e+02 +15 7517 7.674399e+02 5.043700e+02 +19 7517 5.112700e+02 8.035300e+02 +4 7518 -8.671997e+01 6.043101e+02 +15 7518 6.514399e+02 5.026600e+02 +4 7519 -3.221100e+02 6.074399e+02 +15 7519 3.797000e+02 5.005500e+02 +4 7520 -1.009830e+03 6.313900e+02 +15 7520 -3.292300e+02 5.190601e+02 +4 7521 -1.458710e+03 6.395500e+02 +15 7521 -7.565200e+02 5.200900e+02 +4 7522 -1.477800e+03 6.411200e+02 +15 7522 -7.733900e+02 5.211000e+02 +4 7523 -1.368400e+02 6.415100e+02 +19 7523 2.254000e+02 8.690300e+02 +4 7524 -1.239710e+03 6.418800e+02 +15 7524 -5.478500e+02 5.276700e+02 +4 7525 -6.433800e+02 6.517700e+02 +15 7525 2.225000e+01 5.388201e+02 +4 7526 -1.057250e+03 6.525500e+02 +15 7526 -3.699800e+02 5.427600e+02 +4 7527 -1.084210e+03 6.544800e+02 +15 7527 -3.962200e+02 5.444200e+02 +4 7528 -1.386890e+03 6.583000e+02 +15 7528 -6.880300e+02 5.414700e+02 +4 7529 -6.790900e+02 6.672600e+02 +15 7529 -3.071002e+01 5.478600e+02 +4 7530 -1.372830e+03 6.669299e+02 +15 7530 -6.747600e+02 5.501300e+02 +4 7531 -1.966801e+02 6.880900e+02 +7 7531 -1.213110e+03 9.462700e+02 +10 7531 -1.563350e+03 2.118201e+02 +14 7531 -2.515900e+02 5.975601e+02 +15 7531 5.247200e+02 5.927000e+02 +16 7531 -6.874900e+02 7.449600e+02 +19 7531 1.155200e+02 9.495100e+02 +4 7532 -1.966801e+02 6.880900e+02 +7 7532 -1.213110e+03 9.462700e+02 +10 7532 -1.563350e+03 2.118201e+02 +14 7532 -2.515900e+02 5.975601e+02 +15 7532 5.247200e+02 5.927000e+02 +16 7532 -6.874900e+02 7.449600e+02 +19 7532 1.155200e+02 9.495100e+02 +20 7532 -1.410380e+03 2.638101e+02 +4 7533 1.476280e+03 1.991100e+02 +5 7533 1.194880e+03 6.487300e+02 +16 7533 9.563400e+02 2.381800e+02 +4 7534 -8.837000e+01 1.994299e+02 +15 7534 6.461500e+02 4.409003e+01 +4 7535 -2.545601e+02 2.179900e+02 +14 7535 -3.102700e+02 1.816300e+02 +16 7535 -7.260400e+02 2.272300e+02 +4 7536 -2.544399e+02 2.250601e+02 +15 7536 4.609399e+02 7.528003e+01 +16 7536 -7.260400e+02 2.272300e+02 +19 7536 1.160034e+00 8.645996e+01 +4 7537 -2.132100e+02 2.307900e+02 +14 7537 -2.786800e+02 1.871700e+02 +15 7537 5.018199e+02 8.152002e+01 +4 7538 -3.320500e+02 2.387400e+02 +19 7538 -1.390200e+02 1.098700e+02 +4 7539 1.261010e+03 2.414900e+02 +16 7539 6.872200e+02 2.716799e+02 +4 7540 -1.923900e+02 2.448301e+02 +14 7540 -2.580800e+02 1.989800e+02 +15 7540 5.271400e+02 9.682001e+01 +16 7540 -6.621700e+02 2.507800e+02 +4 7541 1.224040e+03 2.527900e+02 +5 7541 9.015000e+02 6.565200e+02 +16 7541 6.641100e+02 2.812200e+02 +4 7542 -5.421997e+01 2.909600e+02 +15 7542 6.878300e+02 1.481800e+02 +4 7543 -2.791500e+02 3.187400e+02 +19 7543 -4.100000e+01 2.615500e+02 +4 7544 3.292004e+01 3.202900e+02 +19 7544 5.460100e+02 2.686500e+02 +4 7545 -1.148999e+01 3.212600e+02 +15 7545 7.358500e+02 1.830700e+02 +16 7545 -4.666900e+02 3.382500e+02 +4 7546 -8.716003e+01 3.288401e+02 +16 7546 -5.475300e+02 3.450000e+02 +4 7547 -2.463600e+02 3.421599e+02 +14 7547 -3.076000e+02 2.883400e+02 +15 7547 4.648000e+02 2.069700e+02 +4 7548 -2.463600e+02 3.421599e+02 +14 7548 -3.076000e+02 2.883400e+02 +4 7549 -2.795500e+02 3.837700e+02 +19 7549 -4.105005e+01 3.829000e+02 +4 7550 -2.532700e+02 3.904500e+02 +15 7550 4.569500e+02 2.611300e+02 +4 7551 -2.528700e+02 3.976500e+02 +15 7551 4.575100e+02 2.690601e+02 +16 7551 -7.422800e+02 4.196000e+02 +19 7551 7.319946e+00 4.100000e+02 +4 7552 2.901100e+02 4.222200e+02 +19 7552 9.219800e+02 3.686899e+02 +4 7553 2.624600e+02 4.265200e+02 +15 7553 9.677700e+02 2.944299e+02 +19 7553 8.669600e+02 3.690901e+02 +4 7554 -3.812100e+02 4.343401e+02 +15 7554 3.110100e+02 3.086700e+02 +4 7555 -4.564800e+02 4.380100e+02 +16 7555 -9.089100e+02 4.692100e+02 +4 7556 -8.843994e+01 4.436899e+02 +7 7556 -1.030830e+03 5.542400e+02 +10 7556 -1.417110e+03 -1.618600e+02 +15 7556 6.495601e+02 3.220200e+02 +16 7556 -5.518900e+02 4.706400e+02 +19 7556 3.169399e+02 5.052500e+02 +20 7556 -1.287600e+03 -2.732996e+01 +4 7557 -1.484399e+02 4.434700e+02 +5 7557 -9.760300e+02 6.661200e+02 +10 7557 -1.508450e+03 -1.542500e+02 +15 7557 5.809200e+02 3.215100e+02 +16 7557 -6.206100e+02 4.709700e+02 +19 7557 2.025100e+02 5.030901e+02 +20 7557 -1.357560e+03 -2.291998e+01 +4 7558 3.686899e+02 4.469600e+02 +14 7558 1.195800e+02 3.150900e+02 +19 7558 1.082470e+03 4.331100e+02 +4 7559 -8.957996e+01 4.575901e+02 +7 7559 -1.082840e+03 5.785300e+02 +10 7559 -1.467080e+03 -1.372100e+02 +16 7559 -5.912000e+02 4.871100e+02 +4 7560 -1.018360e+03 4.592100e+02 +15 7560 -3.374700e+02 3.394000e+02 +4 7561 1.474700e+02 4.636799e+02 +16 7561 -3.173500e+02 4.888700e+02 +19 7561 7.458301e+02 5.230300e+02 +4 7562 1.365800e+02 4.665901e+02 +15 7562 8.964000e+02 3.477600e+02 +16 7562 -3.255500e+02 4.937300e+02 +19 7562 7.288000e+02 5.322500e+02 +4 7563 -9.659300e+02 4.664399e+02 +15 7563 -2.827200e+02 3.466400e+02 +4 7564 -9.659300e+02 4.664399e+02 +15 7564 -2.827200e+02 3.466400e+02 +4 7565 -3.976600e+02 4.669500e+02 +15 7565 2.919000e+02 3.445100e+02 +16 7565 -9.224300e+02 4.983800e+02 +4 7566 -9.868100e+02 4.669500e+02 +15 7566 -3.041000e+02 3.473700e+02 +4 7567 -2.623999e+01 4.771000e+02 +16 7567 -4.870500e+02 5.068300e+02 +4 7568 -2.727300e+02 4.857800e+02 +19 7568 -2.651001e+01 5.726000e+02 +4 7569 -1.168320e+03 4.854299e+02 +15 7569 -4.849700e+02 3.656000e+02 +4 7570 -9.364900e+02 4.894900e+02 +15 7570 -2.512900e+02 3.719100e+02 +4 7571 -9.364900e+02 4.894900e+02 +15 7571 -2.512900e+02 3.719100e+02 +4 7572 -9.505600e+02 4.902200e+02 +15 7572 -2.659200e+02 3.724200e+02 +4 7573 -9.525800e+02 4.942900e+02 +15 7573 -2.686500e+02 3.761100e+02 +4 7574 -1.046760e+03 4.947200e+02 +15 7574 -3.638100e+02 3.767400e+02 +4 7575 -1.219800e+03 4.962000e+02 +15 7575 -5.348800e+02 3.766500e+02 +4 7576 -1.246580e+03 5.033201e+02 +15 7576 -5.609900e+02 3.839700e+02 +4 7577 -1.297650e+03 5.062200e+02 +15 7577 -6.103400e+02 3.866200e+02 +4 7578 -1.252530e+03 5.081300e+02 +15 7578 -5.664400e+02 3.887500e+02 +4 7579 -1.355460e+03 5.086000e+02 +15 7579 -6.654900e+02 3.881300e+02 +4 7580 -1.142340e+03 5.144500e+02 +15 7580 -4.585900e+02 3.964800e+02 +4 7581 -6.849400e+02 5.155200e+02 +15 7581 -2.639001e+01 3.926700e+02 +4 7582 -3.594200e+02 5.178000e+02 +15 7582 3.363900e+02 4.017200e+02 +4 7583 -3.342000e+02 5.245701e+02 +16 7583 -8.458200e+02 5.640800e+02 +19 7583 -1.369600e+02 6.367100e+02 +4 7584 -9.128003e+01 5.387200e+02 +5 7584 -9.190000e+02 8.101000e+02 +10 7584 -1.412230e+03 -2.346997e+01 +15 7584 6.462300e+02 4.293600e+02 +20 7584 -1.287440e+03 7.979004e+01 +4 7585 -1.050100e+02 5.495800e+02 +15 7585 6.308101e+02 4.415800e+02 +4 7586 -8.032800e+02 5.575900e+02 +15 7586 -1.564800e+02 4.324399e+02 +4 7587 -4.541000e+02 5.578900e+02 +15 7587 2.302200e+02 4.425701e+02 +4 7588 4.498999e+01 5.687000e+02 +10 7588 -1.228330e+03 -5.260010e+00 +11 7588 -9.639200e+02 6.269100e+02 +14 7588 -4.481000e+01 4.696700e+02 +15 7588 7.999600e+02 4.639800e+02 +4 7589 -1.909998e+01 5.738000e+02 +7 7589 -9.326300e+02 7.452000e+02 +10 7589 -1.307400e+03 1.282996e+01 +15 7589 7.280699e+02 4.696899e+02 +4 7590 -8.438000e+01 5.767400e+02 +5 7590 -9.183200e+02 8.641700e+02 +10 7590 -1.395250e+03 2.800000e+01 +14 7590 -1.517500e+02 4.910200e+02 +16 7590 -5.530300e+02 6.172900e+02 +4 7591 -8.438000e+01 5.767400e+02 +5 7591 -9.183200e+02 8.641700e+02 +7 7591 -1.026790e+03 7.568600e+02 +10 7591 -1.395250e+03 2.800000e+01 +14 7591 -1.517500e+02 4.910200e+02 +15 7591 6.545601e+02 4.719200e+02 +19 7591 3.235500e+02 7.544600e+02 +4 7592 -8.032100e+02 5.773900e+02 +15 7592 -1.548800e+02 4.516300e+02 +19 7592 -9.173500e+02 6.688000e+02 +4 7593 -8.032100e+02 5.773900e+02 +15 7593 -1.548800e+02 4.516300e+02 +19 7593 -9.173500e+02 6.688000e+02 +4 7594 1.196100e+02 5.775400e+02 +14 7594 5.290009e+00 4.651600e+02 +15 7594 8.783101e+02 4.743500e+02 +4 7595 -6.061400e+02 5.805000e+02 +15 7595 6.198999e+01 4.639800e+02 +4 7596 -3.093199e+02 5.809100e+02 +16 7596 -8.175300e+02 6.272400e+02 +4 7597 -1.676300e+02 5.828600e+02 +5 7597 -1.037120e+03 8.562900e+02 +7 7597 -1.159520e+03 7.768400e+02 +10 7597 -1.524600e+03 5.315002e+01 +14 7597 -2.270800e+02 5.021500e+02 +15 7597 5.587100e+02 4.770701e+02 +19 7597 1.669200e+02 7.609700e+02 +4 7598 -2.627100e+02 5.835000e+02 +5 7598 -1.166260e+03 8.368700e+02 +7 7598 -1.327530e+03 7.921100e+02 +10 7598 -1.698190e+03 7.498999e+01 +15 7598 4.479900e+02 4.755000e+02 +16 7598 -7.618900e+02 6.292500e+02 +19 7598 -6.579956e+00 7.502000e+02 +4 7599 -4.490400e+02 5.849200e+02 +15 7599 2.349200e+02 4.719299e+02 +19 7599 -3.405800e+02 7.332700e+02 +4 7600 -3.542800e+02 5.869500e+02 +14 7600 -4.048100e+02 5.143000e+02 +15 7600 3.429399e+02 4.774900e+02 +4 7601 -4.435999e+01 5.887600e+02 +5 7601 -8.628200e+02 8.879700e+02 +7 7601 -9.684800e+02 7.700500e+02 +10 7601 -1.340970e+03 3.812000e+01 +14 7601 -1.176300e+02 4.966600e+02 +15 7601 7.002400e+02 4.855601e+02 +16 7601 -5.103300e+02 6.290601e+02 +19 7601 3.978400e+02 7.762400e+02 +4 7602 -3.556500e+02 5.912400e+02 +14 7602 -4.074200e+02 5.183101e+02 +15 7602 3.398300e+02 4.810601e+02 +16 7602 -8.779400e+02 6.408600e+02 +4 7603 -2.887900e+02 5.950701e+02 +14 7603 -3.419900e+02 5.184700e+02 +15 7603 4.185699e+02 4.876600e+02 +19 7603 -5.407996e+01 7.687400e+02 +4 7604 -1.406440e+03 5.955601e+02 +15 7604 -7.099400e+02 4.763400e+02 +4 7605 -8.141700e+02 5.989800e+02 +15 7605 -1.666100e+02 4.755100e+02 +19 7605 -9.348600e+02 7.047500e+02 +4 7606 -8.239200e+02 6.010400e+02 +15 7606 -1.760900e+02 4.774500e+02 +19 7606 -9.514700e+02 7.079900e+02 +4 7607 -8.112600e+02 6.019100e+02 +15 7607 -1.639800e+02 4.791000e+02 +19 7607 -9.288700e+02 7.096400e+02 +4 7608 -5.887800e+02 6.025900e+02 +15 7608 8.125000e+01 4.872600e+02 +4 7609 -1.655800e+02 6.030300e+02 +10 7609 -1.518730e+03 8.218994e+01 +16 7609 -6.463700e+02 6.484399e+02 +4 7610 -1.442400e+02 6.049500e+02 +14 7610 -2.035000e+02 5.207000e+02 +4 7611 -1.475200e+02 6.087500e+02 +15 7611 5.822000e+02 5.066400e+02 +4 7612 -6.288400e+02 6.126500e+02 +15 7612 3.723999e+01 4.972800e+02 +4 7613 -1.219870e+03 6.265200e+02 +15 7613 -5.307500e+02 5.125400e+02 +4 7614 -1.219870e+03 6.265200e+02 +15 7614 -5.307500e+02 5.125400e+02 +4 7615 -1.463190e+03 6.314200e+02 +15 7615 -7.611500e+02 5.125601e+02 +4 7616 -1.105640e+03 6.361600e+02 +15 7616 -4.183200e+02 5.247100e+02 +4 7617 -1.407900e+03 6.360800e+02 +15 7617 -7.087500e+02 5.179800e+02 +4 7618 -1.112210e+03 6.364100e+02 +15 7618 -4.248600e+02 5.247900e+02 +4 7619 -1.384340e+03 6.375900e+02 +15 7619 -6.873600e+02 5.200400e+02 +4 7620 -1.211800e+03 6.399100e+02 +15 7620 -5.211700e+02 5.264399e+02 +4 7621 -1.286670e+03 6.451400e+02 +15 7621 -5.932100e+02 5.301200e+02 +4 7622 -1.735601e+02 6.455100e+02 +5 7622 -1.061040e+03 9.424301e+02 +7 7622 -1.173630e+03 8.761400e+02 +10 7622 -1.530190e+03 1.451899e+02 +14 7622 -2.314400e+02 5.581801e+02 +15 7622 5.517200e+02 5.465800e+02 +19 7622 1.561400e+02 8.747500e+02 +4 7623 -1.299830e+03 6.457500e+02 +15 7623 -6.065700e+02 5.306100e+02 +4 7624 -1.684800e+02 6.460601e+02 +5 7624 -1.053140e+03 9.445500e+02 +7 7624 -1.163600e+03 8.758700e+02 +10 7624 -1.520600e+03 1.445500e+02 +15 7624 5.579700e+02 5.472400e+02 +20 7624 -1.373670e+03 2.093201e+02 +4 7625 -1.357100e+03 6.541000e+02 +15 7625 -6.598200e+02 5.372200e+02 +4 7626 -1.096710e+03 6.593900e+02 +15 7626 -4.084400e+02 5.490601e+02 +4 7627 -5.840002e+01 6.721000e+02 +14 7627 -1.269900e+02 5.592700e+02 +15 7627 6.839000e+02 5.761799e+02 +16 7627 -5.283900e+02 7.177200e+02 +4 7628 -1.415180e+03 6.743400e+02 +15 7628 -7.135000e+02 5.570300e+02 +4 7629 -7.970996e+01 6.763000e+02 +15 7629 6.518800e+02 5.812600e+02 +4 7630 7.865002e+01 6.790400e+02 +19 7630 6.244500e+02 8.904200e+02 +4 7631 -5.446900e+02 6.884200e+02 +15 7631 1.213400e+02 5.777000e+02 +4 7632 3.621997e+01 2.054800e+02 +15 7632 7.884301e+02 4.928998e+01 +4 7633 1.578003e+01 2.054000e+02 +15 7633 7.651899e+02 4.937000e+01 +4 7634 -1.000300e+02 2.197600e+02 +15 7634 7.189900e+02 6.658002e+01 +4 7635 -2.338300e+02 2.219000e+02 +14 7635 -2.992500e+02 1.790200e+02 +15 7635 4.771200e+02 7.154999e+01 +16 7635 -7.115700e+02 2.236800e+02 +4 7636 -1.858700e+02 2.257400e+02 +14 7636 -2.514300e+02 1.816800e+02 +15 7636 5.346500e+02 7.528003e+01 +16 7636 -6.523500e+02 2.296200e+02 +19 7636 1.309800e+02 9.093994e+01 +4 7637 -1.858700e+02 2.257400e+02 +14 7637 -2.514300e+02 1.816800e+02 +15 7637 5.346500e+02 7.528003e+01 +16 7637 -6.523500e+02 2.296200e+02 +19 7637 1.309800e+02 9.093994e+01 +4 7638 -4.408997e+01 2.264099e+02 +15 7638 6.994200e+02 7.447998e+01 +4 7639 -4.864001e+01 2.264700e+02 +15 7639 6.930300e+02 7.447998e+01 +4 7640 -1.555200e+02 2.319500e+02 +15 7640 5.692300e+02 8.183002e+01 +4 7641 -1.652900e+02 2.382600e+02 +19 7641 1.704000e+02 1.148201e+02 +4 7642 -2.778101e+02 2.393900e+02 +15 7642 4.251801e+02 9.160999e+01 +19 7642 -4.069995e+01 1.125801e+02 +4 7643 -2.914200e+02 2.394500e+02 +19 7643 -6.600000e+01 1.123000e+02 +4 7644 -3.177800e+02 2.394299e+02 +19 7644 -1.142100e+02 1.122100e+02 +4 7645 -2.551300e+02 2.400000e+02 +19 7645 5.300293e-01 1.148700e+02 +4 7646 -1.609700e+02 2.414399e+02 +14 7646 -2.299900e+02 1.947700e+02 +15 7646 5.623000e+02 9.278003e+01 +16 7646 -6.261200e+02 2.477100e+02 +19 7646 1.784800e+02 1.201000e+02 +4 7647 -1.685500e+02 2.503500e+02 +14 7647 -2.370600e+02 2.022300e+02 +15 7647 5.542600e+02 1.020200e+02 +19 7647 1.640500e+02 1.367800e+02 +4 7648 9.258997e+01 2.873000e+02 +15 7648 8.503400e+02 1.434700e+02 +4 7649 -2.522800e+02 2.936599e+02 +14 7649 -3.160200e+02 2.444800e+02 +19 7649 7.550049e+00 2.159800e+02 +4 7650 -2.162600e+02 3.132200e+02 +15 7650 4.990300e+02 1.742000e+02 +19 7650 7.252002e+01 2.550400e+02 +4 7651 5.430005e+01 3.140300e+02 +14 7651 -4.451999e+01 2.490200e+02 +19 7651 5.855800e+02 2.555601e+02 +4 7652 -1.894301e+02 3.138201e+02 +15 7652 5.326300e+02 1.751900e+02 +4 7653 -3.141300e+02 3.184900e+02 +19 7653 -1.060800e+02 2.594600e+02 +4 7654 -2.572400e+02 3.195701e+02 +15 7654 4.512800e+02 1.818000e+02 +19 7654 -1.650024e+00 2.641699e+02 +4 7655 2.715002e+01 3.211400e+02 +19 7655 5.356200e+02 2.710601e+02 +4 7656 -3.640015e+00 3.210400e+02 +16 7656 -4.564100e+02 3.378000e+02 +4 7657 1.153990e+03 3.217400e+02 +16 7657 6.186500e+02 3.459200e+02 +4 7658 -3.115601e+02 3.215701e+02 +19 7658 -1.013101e+02 2.651000e+02 +4 7659 -4.146997e+01 3.217700e+02 +15 7659 7.021500e+02 1.836700e+02 +16 7659 -4.969100e+02 3.383500e+02 +4 7660 -1.854700e+02 3.218900e+02 +15 7660 5.360900e+02 1.843700e+02 +4 7661 1.030500e+02 3.223800e+02 +15 7661 8.615699e+02 1.826700e+02 +4 7662 2.895996e+01 3.245400e+02 +19 7662 5.375100e+02 2.772300e+02 +4 7663 -4.623999e+01 3.254500e+02 +15 7663 6.955601e+02 1.878100e+02 +4 7664 -2.184900e+02 3.277100e+02 +15 7664 4.970100e+02 1.912200e+02 +16 7664 -6.968900e+02 3.442600e+02 +19 7664 7.102002e+01 2.837500e+02 +4 7665 1.160330e+03 3.284900e+02 +16 7665 6.235300e+02 3.521100e+02 +4 7666 -1.359700e+02 3.292200e+02 +19 7666 2.290800e+02 2.885901e+02 +4 7667 -1.400699e+02 3.320200e+02 +15 7667 5.894800e+02 1.957600e+02 +16 7667 -6.048400e+02 3.481400e+02 +19 7667 2.194100e+02 2.938301e+02 +4 7668 -3.814001e+01 3.328700e+02 +15 7668 7.048500e+02 1.957300e+02 +16 7668 -4.946700e+02 3.489100e+02 +4 7669 1.269000e+02 3.419299e+02 +10 7669 -1.166270e+03 -3.277200e+02 +15 7669 8.870601e+02 2.056600e+02 +16 7669 -3.296400e+02 3.616600e+02 +20 7669 -1.108440e+03 -1.442500e+02 +4 7670 7.881995e+01 3.463700e+02 +16 7670 -3.744400e+02 3.652400e+02 +4 7671 7.892004e+01 3.637000e+02 +14 7671 -2.529001e+01 2.893500e+02 +15 7671 8.369800e+02 2.310500e+02 +16 7671 -3.749400e+02 3.842400e+02 +19 7671 6.307500e+02 3.480901e+02 +4 7672 1.037400e+02 3.638201e+02 +14 7672 -9.079987e+00 2.867500e+02 +15 7672 8.630601e+02 2.308200e+02 +4 7673 4.650000e+01 3.639900e+02 +15 7673 8.011000e+02 2.313800e+02 +4 7674 -1.055800e+02 3.642500e+02 +14 7674 -1.757600e+02 3.030500e+02 +19 7674 2.843400e+02 3.550500e+02 +4 7675 9.331995e+01 3.649399e+02 +19 7675 6.575200e+02 3.478000e+02 +4 7676 -1.794700e+02 3.810400e+02 +15 7676 5.442400e+02 2.510500e+02 +4 7677 -3.508400e+02 3.815701e+02 +19 7677 -1.706500e+02 3.741000e+02 +4 7678 -2.145900e+02 3.842500e+02 +14 7678 -2.756300e+02 3.262400e+02 +15 7678 5.034600e+02 2.546500e+02 +19 7678 7.919995e+01 3.896300e+02 +4 7679 -9.983997e+01 3.874800e+02 +15 7679 6.361400e+02 2.587500e+02 +4 7680 2.823101e+02 4.206300e+02 +19 7680 9.078501e+02 3.651400e+02 +4 7681 2.823101e+02 4.206300e+02 +19 7681 9.078501e+02 3.651400e+02 +4 7682 4.116200e+02 4.292500e+02 +18 7682 -1.135190e+03 1.759399e+02 +20 7682 -9.760100e+02 -4.777002e+01 +4 7683 3.402800e+02 4.298401e+02 +19 7683 1.022970e+03 3.943201e+02 +4 7684 3.075900e+02 4.341100e+02 +16 7684 -2.131100e+02 4.511600e+02 +19 7684 9.562300e+02 3.925400e+02 +4 7685 -3.185900e+02 4.365400e+02 +15 7685 3.825300e+02 3.118300e+02 +19 7685 -1.108300e+02 4.777000e+02 +4 7686 -3.580900e+02 4.377700e+02 +15 7686 3.367700e+02 3.126300e+02 +4 7687 1.087600e+02 4.415000e+02 +10 7687 -1.230120e+03 -1.740900e+02 +4 7688 -4.002200e+02 4.425300e+02 +16 7688 -8.375200e+02 4.740200e+02 +4 7689 9.059998e+01 4.440200e+02 +10 7689 -1.258740e+03 -1.680900e+02 +15 7689 8.493300e+02 3.230800e+02 +19 7689 6.489700e+02 4.987700e+02 +20 7689 -1.171450e+03 -2.763000e+01 +4 7690 4.115000e+02 4.449000e+02 +14 7690 1.629100e+02 3.153600e+02 +18 7690 -1.135350e+03 1.951699e+02 +4 7691 3.628199e+02 4.451400e+02 +16 7691 -1.455500e+02 4.633600e+02 +4 7692 3.603199e+02 4.476599e+02 +14 7692 1.115100e+02 3.152700e+02 +4 7693 2.857996e+01 4.493500e+02 +14 7693 -6.106000e+01 3.682600e+02 +15 7693 7.821500e+02 3.289700e+02 +4 7694 -1.457400e+02 4.511699e+02 +15 7694 5.841100e+02 3.302400e+02 +19 7694 2.093101e+02 5.182200e+02 +4 7695 -1.182300e+03 4.559199e+02 +15 7695 -5.011200e+02 3.344700e+02 +4 7696 1.231400e+02 4.587200e+02 +14 7696 -2.689999e+01 3.770800e+02 +4 7697 -1.278270e+03 4.592400e+02 +15 7697 -5.945700e+02 3.373300e+02 +4 7698 -1.103750e+03 4.605400e+02 +15 7698 -4.226000e+02 3.400500e+02 +4 7699 -9.909700e+02 4.646599e+02 +15 7699 -3.082500e+02 3.440900e+02 +4 7700 8.731995e+01 4.693201e+02 +16 7700 -3.704600e+02 4.970400e+02 +4 7701 -7.966600e+02 4.720801e+02 +19 7701 -9.125200e+02 4.909600e+02 +4 7702 -7.966600e+02 4.720801e+02 +19 7702 -9.125200e+02 4.909600e+02 +4 7703 -2.453500e+02 4.726100e+02 +15 7703 4.681700e+02 3.529200e+02 +4 7704 -1.454600e+02 4.738800e+02 +10 7704 -1.502000e+03 -1.098500e+02 +14 7704 -2.090200e+02 4.034500e+02 +15 7704 5.843199e+02 3.556400e+02 +16 7704 -6.185600e+02 5.047500e+02 +19 7704 2.100699e+02 5.606000e+02 +4 7705 4.545000e+02 4.810801e+02 +16 7705 -4.234003e+01 5.011799e+02 +4 7706 -3.438400e+02 4.826500e+02 +15 7706 3.537900e+02 3.635601e+02 +16 7706 -8.553700e+02 5.154200e+02 +4 7707 -9.757700e+02 4.823900e+02 +15 7707 -2.924100e+02 3.642800e+02 +4 7708 -1.003280e+03 4.835500e+02 +15 7708 -3.203900e+02 3.650601e+02 +4 7709 -2.865200e+02 4.842500e+02 +15 7709 4.196200e+02 3.652900e+02 +4 7710 -1.014500e+03 4.935400e+02 +15 7710 -3.311100e+02 3.756500e+02 +4 7711 -9.057996e+01 4.948000e+02 +15 7711 6.457000e+02 3.798600e+02 +4 7712 -9.806995e+01 4.949800e+02 +15 7712 6.390300e+02 3.800701e+02 +4 7713 -1.320300e+03 4.972900e+02 +15 7713 -6.318800e+02 3.770000e+02 +4 7714 -1.152010e+03 4.995200e+02 +15 7714 -4.686400e+02 3.808700e+02 +4 7715 -1.317190e+03 5.002300e+02 +15 7715 -6.292300e+02 3.798800e+02 +4 7716 -1.066140e+03 5.102400e+02 +15 7716 -3.827000e+02 3.922900e+02 +4 7717 -1.046120e+03 5.104800e+02 +15 7717 -3.627300e+02 3.932100e+02 +4 7718 -1.059590e+03 5.112000e+02 +15 7718 -3.761000e+02 3.941400e+02 +4 7719 4.416600e+02 5.121799e+02 +16 7719 -5.992999e+01 5.321200e+02 +4 7720 -1.101430e+03 5.122600e+02 +15 7720 -4.182600e+02 3.949000e+02 +4 7721 2.923400e+02 5.155300e+02 +19 7721 9.093601e+02 5.140901e+02 +4 7722 -3.585601e+02 5.236700e+02 +15 7722 3.376000e+02 4.071700e+02 +4 7723 -2.925400e+02 5.245800e+02 +15 7723 4.129399e+02 4.096400e+02 +16 7723 -7.957000e+02 5.629700e+02 +19 7723 -6.212000e+01 6.412900e+02 +4 7724 -2.642700e+02 5.260300e+02 +7 7724 -1.328260e+03 7.002400e+02 +10 7724 -1.708210e+03 -1.133997e+01 +14 7724 -3.198600e+02 4.554700e+02 +15 7724 4.459301e+02 4.119900e+02 +16 7724 -7.609500e+02 5.644000e+02 +19 7724 -1.034998e+01 6.468101e+02 +4 7725 1.476700e+02 5.269299e+02 +19 7725 7.440000e+02 6.378600e+02 +4 7726 -2.880300e+02 5.283201e+02 +15 7726 4.186100e+02 4.136300e+02 +4 7727 -2.669900e+02 5.287600e+02 +16 7727 -7.644500e+02 5.669100e+02 +4 7728 -3.344600e+02 5.311000e+02 +14 7728 -3.874600e+02 4.626200e+02 +15 7728 3.645900e+02 4.165900e+02 +19 7728 -1.379200e+02 6.481200e+02 +4 7729 -5.294995e+01 5.381500e+02 +7 7729 -9.791300e+02 6.946000e+02 +10 7729 -1.355770e+03 -3.181995e+01 +14 7729 -1.254500e+02 4.533101e+02 +15 7729 6.905601e+02 4.285900e+02 +20 7729 -1.244320e+03 7.417993e+01 +4 7730 -1.011000e+03 5.419500e+02 +15 7730 -3.319200e+02 4.242100e+02 +4 7731 1.443500e+02 5.438000e+02 +19 7731 7.412200e+02 6.709600e+02 +4 7732 1.261700e+02 5.474000e+02 +14 7732 1.007999e+01 4.384200e+02 +15 7732 8.860900e+02 4.397200e+02 +4 7733 -4.510200e+02 5.539600e+02 +15 7733 2.336801e+02 4.387600e+02 +4 7734 -3.873300e+02 5.549399e+02 +14 7734 -4.376000e+02 4.869600e+02 +19 7734 -2.319600e+02 6.867500e+02 +4 7735 -7.948200e+02 5.561400e+02 +15 7735 -1.489400e+02 4.317400e+02 +4 7736 9.607996e+01 5.566799e+02 +14 7736 -9.019989e+00 4.510800e+02 +15 7736 8.550300e+02 4.501000e+02 +16 7736 -3.651400e+02 5.898900e+02 +19 7736 6.578601e+02 7.064299e+02 +4 7737 -1.700699e+02 5.578600e+02 +15 7737 5.558600e+02 4.488000e+02 +4 7738 -8.538300e+02 5.587100e+02 +15 7738 -2.079000e+02 4.336200e+02 +4 7739 -3.678900e+02 5.594600e+02 +14 7739 -4.189100e+02 4.898101e+02 +15 7739 3.272000e+02 4.464800e+02 +16 7739 -8.906200e+02 6.042900e+02 +19 7739 -1.980200e+02 6.959900e+02 +4 7740 -3.544700e+02 5.598300e+02 +14 7740 -4.057400e+02 4.895200e+02 +15 7740 3.426801e+02 4.471400e+02 +16 7740 -8.734600e+02 6.047900e+02 +19 7740 -1.738800e+02 6.982500e+02 +4 7741 -5.914100e+02 5.626700e+02 +15 7741 7.693994e+01 4.449800e+02 +4 7742 -1.433101e+02 5.635200e+02 +16 7742 -6.182300e+02 6.041300e+02 +4 7743 -2.439301e+02 5.636100e+02 +14 7743 -2.996000e+02 4.879900e+02 +4 7744 -2.770500e+02 5.646899e+02 +16 7744 -7.782100e+02 6.081000e+02 +4 7745 -6.173000e+02 5.651799e+02 +15 7745 4.856995e+01 4.464000e+02 +4 7746 -3.043994e+01 5.658500e+02 +15 7746 7.157600e+02 4.602600e+02 +4 7747 -1.410400e+02 5.667700e+02 +15 7747 5.904200e+02 4.597900e+02 +16 7747 -6.155200e+02 6.075200e+02 +19 7747 2.185000e+02 7.338201e+02 +4 7748 -6.548400e+02 5.707900e+02 +15 7748 7.790039e+00 4.520300e+02 +4 7749 -4.589200e+02 5.714700e+02 +19 7749 -3.574900e+02 7.092700e+02 +4 7750 1.076001e+01 5.782200e+02 +10 7750 -1.265780e+03 1.359998e+01 +15 7750 7.632500e+02 4.748600e+02 +20 7750 -1.177910e+03 1.116300e+02 +4 7751 -6.027300e+02 5.782200e+02 +15 7751 6.540002e+01 4.626000e+02 +4 7752 -1.666500e+02 5.787900e+02 +15 7752 5.605900e+02 4.728201e+02 +4 7753 -3.843994e+01 5.815100e+02 +5 7753 -8.544200e+02 8.798500e+02 +10 7753 -1.330700e+03 2.704004e+01 +15 7753 7.069500e+02 4.778201e+02 +19 7753 4.106801e+02 7.645500e+02 +4 7754 2.828003e+01 5.834600e+02 +15 7754 7.808900e+02 4.807000e+02 +16 7754 -4.337200e+02 6.211300e+02 +19 7754 5.342800e+02 7.628600e+02 +4 7755 -8.314500e+02 5.832300e+02 +15 7755 -1.845400e+02 4.592000e+02 +19 7755 -9.643700e+02 6.814600e+02 +4 7756 6.598999e+01 5.852300e+02 +10 7756 -1.207900e+03 1.383997e+01 +15 7756 8.225100e+02 4.823900e+02 +18 7756 -1.330560e+03 3.680500e+02 +4 7757 -2.881006e+01 5.871500e+02 +15 7757 7.187400e+02 4.843600e+02 +4 7758 -1.655400e+02 5.869800e+02 +14 7758 -2.236300e+02 5.057300e+02 +4 7759 -1.609998e+01 5.875100e+02 +7 7759 -9.287800e+02 7.646700e+02 +10 7759 -1.303870e+03 3.106995e+01 +15 7759 7.319600e+02 4.843101e+02 +4 7760 7.894995e+01 5.880800e+02 +15 7760 8.361700e+02 4.861899e+02 +16 7760 -3.829300e+02 6.245500e+02 +19 7760 6.264600e+02 7.670900e+02 +4 7761 6.593994e+01 5.898600e+02 +19 7761 6.021600e+02 7.703000e+02 +4 7762 -8.034998e+01 5.923000e+02 +16 7762 -5.493200e+02 6.339500e+02 +4 7763 -9.133500e+02 5.983300e+02 +15 7763 -2.676000e+02 4.733201e+02 +4 7764 -4.205699e+02 6.007800e+02 +15 7764 2.660100e+02 4.916000e+02 +19 7764 -2.882800e+02 7.640100e+02 +4 7765 -1.008450e+03 6.063600e+02 +15 7765 -3.291200e+02 4.930300e+02 +4 7766 -9.633997e+01 6.087500e+02 +19 7766 3.006000e+02 8.125800e+02 +4 7767 -8.385000e+02 6.090601e+02 +19 7767 -9.760900e+02 7.242300e+02 +4 7768 -6.693900e+02 6.096700e+02 +15 7768 -6.859985e+00 4.930601e+02 +4 7769 -6.693900e+02 6.096700e+02 +15 7769 -6.859985e+00 4.930601e+02 +4 7770 -5.946000e+02 6.098900e+02 +15 7770 7.402002e+01 4.951899e+02 +4 7771 -5.946000e+02 6.098900e+02 +15 7771 7.402002e+01 4.951899e+02 +4 7772 -6.646800e+02 6.099299e+02 +15 7772 -1.179993e+00 4.936100e+02 +4 7773 -1.113170e+03 6.106899e+02 +15 7773 -4.265800e+02 4.973800e+02 +4 7774 -6.499000e+02 6.110500e+02 +15 7774 1.427002e+01 4.949500e+02 +4 7775 -1.307300e+02 6.117500e+02 +15 7775 5.999700e+02 5.104200e+02 +4 7776 -6.444200e+02 6.116799e+02 +15 7776 2.005005e+01 4.960900e+02 +4 7777 -6.391700e+02 6.121100e+02 +15 7777 2.572998e+01 4.965701e+02 +4 7778 -6.240400e+02 6.132400e+02 +15 7778 4.279004e+01 4.982400e+02 +4 7779 -6.187500e+02 6.136799e+02 +15 7779 4.806006e+01 4.987300e+02 +4 7780 -1.470601e+02 6.144900e+02 +16 7780 -6.255000e+02 6.604399e+02 +4 7781 -5.938400e+02 6.145300e+02 +15 7781 7.381995e+01 4.998300e+02 +4 7782 -6.356800e+02 6.157300e+02 +15 7782 3.038000e+01 5.005200e+02 +4 7783 -6.304200e+02 6.162900e+02 +15 7783 3.570996e+01 5.013400e+02 +4 7784 -6.482800e+02 6.176200e+02 +15 7784 1.680005e+01 5.021100e+02 +4 7785 -1.157950e+03 6.224600e+02 +15 7785 -4.699700e+02 5.095300e+02 +4 7786 -6.255400e+02 6.231700e+02 +15 7786 4.092004e+01 5.087800e+02 +4 7787 -9.827400e+02 6.235800e+02 +15 7787 -3.051700e+02 5.104399e+02 +4 7788 -1.584900e+02 6.243000e+02 +16 7788 -6.394600e+02 6.724100e+02 +19 7788 1.855300e+02 8.372700e+02 +4 7789 -9.914500e+02 6.260701e+02 +15 7789 -3.133300e+02 5.131700e+02 +4 7790 -5.969400e+02 6.312900e+02 +15 7790 7.081006e+01 5.176000e+02 +4 7791 -5.455005e+01 6.338700e+02 +7 7791 -9.839100e+02 8.402300e+02 +10 7791 -1.348800e+03 1.029600e+02 +4 7792 -5.455005e+01 6.338700e+02 +15 7792 6.889900e+02 5.363600e+02 +4 7793 -1.323380e+03 6.340500e+02 +15 7793 -6.301300e+02 5.181200e+02 +4 7794 -1.079580e+03 6.343800e+02 +15 7794 -3.922700e+02 5.233000e+02 +4 7795 -1.086280e+03 6.344800e+02 +15 7795 -3.988300e+02 5.233101e+02 +4 7796 -8.706000e+02 6.362300e+02 +19 7796 -1.023740e+03 7.667800e+02 +4 7797 1.288000e+01 6.417400e+02 +10 7797 -1.359170e+03 1.229900e+02 +15 7797 7.627800e+02 5.474200e+02 +4 7798 -1.444500e+02 6.421500e+02 +7 7798 -1.125430e+03 8.648400e+02 +10 7798 -1.484560e+03 1.315699e+02 +14 7798 -2.047300e+02 5.514900e+02 +15 7798 5.849500e+02 5.432900e+02 +16 7798 -6.244200e+02 6.909200e+02 +20 7798 -1.347110e+03 2.001200e+02 +4 7799 -1.918500e+02 6.442700e+02 +7 7799 -1.203440e+03 8.770100e+02 +10 7799 -1.560680e+03 1.475500e+02 +14 7799 -2.479800e+02 5.581600e+02 +15 7799 5.307800e+02 5.447800e+02 +16 7799 -6.801400e+02 6.955300e+02 +19 7799 1.236500e+02 8.707100e+02 +20 7799 -1.405440e+03 2.118800e+02 +4 7800 -1.918500e+02 6.442700e+02 +15 7800 5.307800e+02 5.447800e+02 +4 7801 -1.282390e+03 6.480800e+02 +15 7801 -5.894800e+02 5.330900e+02 +4 7802 4.489990e+00 6.488101e+02 +16 7802 -4.634200e+02 6.920500e+02 +19 7802 4.880699e+02 8.780500e+02 +4 7803 -1.336090e+03 6.489200e+02 +15 7803 -6.406100e+02 5.328400e+02 +4 7804 -2.203101e+02 6.492500e+02 +14 7804 -2.746300e+02 5.641600e+02 +4 7805 -1.349090e+03 6.530000e+02 +15 7805 -6.523100e+02 5.365500e+02 +4 7806 -1.362140e+03 6.537300e+02 +15 7806 -6.645400e+02 5.369299e+02 +4 7807 -2.327300e+02 6.692500e+02 +14 7807 -2.894300e+02 5.724301e+02 +15 7807 4.823300e+02 5.696500e+02 +4 7808 -5.441500e+02 6.723800e+02 +15 7808 1.214399e+02 5.611000e+02 +4 7809 -1.419720e+03 6.735701e+02 +15 7809 -7.178800e+02 5.560400e+02 +4 7810 -1.318500e+02 6.807400e+02 +19 7810 2.339700e+02 9.233900e+02 +4 7811 -5.970200e+02 6.927900e+02 +19 7811 -5.872300e+02 9.014399e+02 +4 7812 -1.119100e+02 7.049399e+02 +14 7812 -1.890400e+02 5.900500e+02 +4 7813 -2.205400e+02 7.133000e+02 +15 7813 4.950100e+02 6.191100e+02 +4 7814 -1.704399e+02 2.287100e+02 +15 7814 5.519700e+02 7.838000e+01 +16 7814 -6.365400e+02 2.333400e+02 +19 7814 1.610200e+02 9.580005e+01 +4 7815 4.771997e+01 2.293500e+02 +16 7815 -4.012400e+02 2.393300e+02 +4 7816 -2.806801e+02 2.373600e+02 +19 7816 -4.521997e+01 1.103101e+02 +4 7817 6.159998e+01 2.435701e+02 +15 7817 8.168101e+02 9.304999e+01 +4 7818 -2.447998e+01 2.443900e+02 +15 7818 7.203300e+02 9.464001e+01 +4 7819 -1.706300e+02 2.445100e+02 +14 7819 -2.385500e+02 1.979000e+02 +15 7819 5.513800e+02 9.590997e+01 +16 7819 -6.375400e+02 2.506000e+02 +19 7819 1.607200e+02 1.255500e+02 +4 7820 3.489990e+00 2.546899e+02 +15 7820 7.529301e+02 1.056500e+02 +4 7821 7.929004e+01 2.744800e+02 +15 7821 8.362700e+02 1.282800e+02 +4 7822 1.662000e+01 2.781500e+02 +19 7822 5.162300e+02 1.890601e+02 +4 7823 1.662000e+01 2.781500e+02 +19 7823 5.162300e+02 1.890601e+02 +4 7824 -2.885900e+02 2.796799e+02 +19 7824 -5.989001e+01 1.870701e+02 +4 7825 -1.819700e+02 2.811599e+02 +15 7825 5.400300e+02 1.381000e+02 +4 7826 -2.524900e+02 2.827800e+02 +14 7826 -3.164300e+02 2.344600e+02 +4 7827 -2.455800e+02 2.934800e+02 +14 7827 -3.079900e+02 2.442400e+02 +4 7828 -8.756995e+01 3.062200e+02 +15 7828 6.190200e+02 1.663600e+02 +4 7829 -1.325100e+02 3.059500e+02 +15 7829 5.980400e+02 1.663000e+02 +16 7829 -5.961000e+02 3.198300e+02 +4 7830 -1.325100e+02 3.059500e+02 +15 7830 5.980400e+02 1.663000e+02 +4 7831 9.080005e+01 3.077200e+02 +15 7831 8.507200e+02 1.666100e+02 +4 7832 -2.037100e+02 3.105200e+02 +14 7832 -2.661200e+02 2.595600e+02 +4 7833 3.839966e+00 3.174299e+02 +19 7833 4.924700e+02 2.644000e+02 +4 7834 -3.175100e+02 3.209000e+02 +19 7834 -1.123000e+02 2.639199e+02 +4 7835 1.647998e+01 3.239600e+02 +15 7835 7.677100e+02 1.857000e+02 +16 7835 -4.357300e+02 3.412800e+02 +19 7835 5.150100e+02 2.771100e+02 +4 7836 -3.248800e+02 3.259700e+02 +19 7836 -1.258600e+02 2.719800e+02 +4 7837 -3.248800e+02 3.259700e+02 +19 7837 -1.258600e+02 2.719800e+02 +4 7838 -1.737200e+02 3.280500e+02 +15 7838 5.493500e+02 1.905700e+02 +16 7838 -6.449600e+02 3.429600e+02 +4 7839 7.846997e+01 3.414600e+02 +15 7839 8.361700e+02 2.048400e+02 +19 7839 6.300400e+02 3.045500e+02 +4 7840 -1.888400e+02 3.485100e+02 +14 7840 -2.524800e+02 2.931300e+02 +19 7840 1.262000e+02 3.237700e+02 +4 7841 7.181006e+01 3.625701e+02 +14 7841 -3.094000e+01 2.888300e+02 +16 7841 -3.818700e+02 3.825900e+02 +18 7841 -1.327390e+03 9.089001e+01 +4 7842 -1.500500e+02 3.679700e+02 +14 7842 -2.167400e+02 3.083300e+02 +4 7843 -1.500500e+02 3.679700e+02 +14 7843 -2.167400e+02 3.083300e+02 +19 7843 1.995300e+02 3.604199e+02 +4 7844 -2.378199e+02 3.846699e+02 +16 7844 -7.229600e+02 4.055400e+02 +19 7844 3.514001e+01 3.867100e+02 +4 7845 -2.046600e+02 3.854299e+02 +15 7845 5.152500e+02 2.559700e+02 +19 7845 9.879004e+01 3.931000e+02 +4 7846 -2.103500e+02 3.873900e+02 +19 7846 8.614001e+01 3.958600e+02 +4 7847 3.017004e+01 3.879000e+02 +19 7847 5.394301e+02 3.969099e+02 +4 7848 -1.079700e+02 3.881799e+02 +15 7848 6.269600e+02 2.595000e+02 +19 7848 2.807400e+02 4.005200e+02 +4 7849 -2.606400e+02 3.911500e+02 +15 7849 4.477800e+02 2.616300e+02 +16 7849 -7.510700e+02 4.127100e+02 +19 7849 -6.079956e+00 3.972300e+02 +4 7850 1.260090e+03 4.016300e+02 +16 7850 6.597100e+02 4.166000e+02 +4 7851 1.535100e+02 4.356300e+02 +15 7851 9.120300e+02 3.122100e+02 +19 7851 7.570400e+02 4.678500e+02 +4 7852 -1.823700e+02 4.389900e+02 +15 7852 5.407400e+02 3.162900e+02 +4 7853 -1.059399e+02 4.405701e+02 +15 7853 6.305000e+02 3.186799e+02 +4 7854 -1.575400e+02 4.486000e+02 +15 7854 5.697300e+02 3.268400e+02 +4 7855 -1.025550e+03 4.515601e+02 +15 7855 -3.446900e+02 3.304900e+02 +4 7856 -1.034930e+03 4.524500e+02 +15 7856 -3.540100e+02 3.310400e+02 +4 7857 -1.482700e+02 4.708000e+02 +5 7857 -9.825000e+02 7.038700e+02 +10 7857 -1.507550e+03 -1.137500e+02 +15 7857 5.806100e+02 3.522600e+02 +4 7858 -9.584000e+02 4.736899e+02 +15 7858 -2.753400e+02 3.548700e+02 +4 7859 -1.479500e+02 4.763600e+02 +15 7859 5.805800e+02 3.584900e+02 +4 7860 -1.479500e+02 4.763600e+02 +15 7860 5.805800e+02 3.584900e+02 +4 7861 -4.520300e+02 4.788201e+02 +16 7861 -9.049800e+02 5.160601e+02 +4 7862 -9.940400e+02 4.792900e+02 +15 7862 -3.104100e+02 3.605800e+02 +4 7863 -3.786899e+02 4.840701e+02 +16 7863 -8.997400e+02 5.176600e+02 +4 7864 -2.474600e+02 4.887400e+02 +15 7864 4.656100e+02 3.712900e+02 +4 7865 -1.136100e+02 4.953101e+02 +10 7865 -1.449000e+03 -8.309998e+01 +15 7865 6.213400e+02 3.804700e+02 +4 7866 -1.763800e+02 5.020400e+02 +15 7866 5.347200e+02 3.859600e+02 +4 7867 -1.741000e+02 5.050000e+02 +16 7867 -6.525700e+02 5.392800e+02 +4 7868 1.352200e+02 5.056300e+02 +10 7868 -1.185500e+03 -8.517004e+01 +4 7869 -6.817400e+02 5.052800e+02 +15 7869 -2.271002e+01 3.817500e+02 +4 7870 -1.125500e+03 5.129000e+02 +15 7870 -4.419300e+02 3.948400e+02 +4 7871 3.132500e+02 5.150601e+02 +19 7871 9.462700e+02 5.138201e+02 +4 7872 -1.259260e+03 5.176000e+02 +15 7872 -5.728800e+02 3.986600e+02 +4 7873 1.370800e+02 5.307800e+02 +19 7873 7.271201e+02 6.491500e+02 +4 7874 4.903800e+02 5.318900e+02 +14 7874 2.190500e+02 3.750100e+02 +18 7874 -1.050120e+03 2.910901e+02 +4 7875 -1.765601e+02 5.459200e+02 +15 7875 5.480601e+02 4.358000e+02 +4 7876 -3.988101e+02 5.544399e+02 +14 7876 -4.486000e+02 4.871200e+02 +19 7876 -2.528199e+02 6.845601e+02 +4 7877 -4.369200e+02 5.547400e+02 +15 7877 2.486700e+02 4.396799e+02 +4 7878 -3.900100e+02 5.572200e+02 +15 7878 3.826100e+02 4.498000e+02 +4 7879 -8.574900e+02 5.577900e+02 +15 7879 -2.109000e+02 4.329200e+02 +4 7880 -5.862800e+02 5.590100e+02 +15 7880 8.235999e+01 4.412000e+02 +4 7881 -1.675000e+02 5.602000e+02 +15 7881 5.589100e+02 4.516600e+02 +4 7882 1.158300e+02 5.716799e+02 +10 7882 -1.162700e+03 -1.185999e+01 +15 7882 8.745300e+02 4.671400e+02 +4 7883 -4.278500e+02 5.731500e+02 +15 7883 2.589600e+02 4.598500e+02 +19 7883 -3.036000e+02 7.134299e+02 +4 7884 -1.262960e+03 5.754200e+02 +15 7884 -5.745600e+02 4.584299e+02 +4 7885 -1.286640e+03 5.756700e+02 +15 7885 -5.972900e+02 4.580200e+02 +4 7886 -1.286640e+03 5.756700e+02 +15 7886 -5.972900e+02 4.580200e+02 +4 7887 -5.993200e+02 5.786000e+02 +15 7887 6.858997e+01 4.616600e+02 +4 7888 -2.004800e+02 5.790100e+02 +15 7888 5.207600e+02 4.721300e+02 +4 7889 -2.004800e+02 5.790100e+02 +15 7889 5.207600e+02 4.721300e+02 +4 7890 2.295996e+01 5.797800e+02 +15 7890 7.763101e+02 4.766100e+02 +19 7890 5.260699e+02 7.580500e+02 +4 7891 -8.034300e+02 5.807900e+02 +19 7891 -9.180200e+02 6.761899e+02 +4 7892 -8.241000e+02 5.825601e+02 +15 7892 -1.771400e+02 4.589000e+02 +4 7893 -1.260900e+02 5.877200e+02 +5 7893 -9.795900e+02 8.712600e+02 +7 7893 -1.092300e+03 7.793800e+02 +10 7893 -1.457820e+03 5.216003e+01 +15 7893 6.064200e+02 4.835500e+02 +20 7893 -1.323150e+03 1.374299e+02 +4 7894 -6.391003e+01 5.879500e+02 +15 7894 6.778700e+02 4.850800e+02 +4 7895 -1.802700e+02 5.908101e+02 +10 7895 -1.545980e+03 6.698999e+01 +4 7896 -1.211899e+02 5.965800e+02 +15 7896 6.123000e+02 4.930601e+02 +4 7897 -8.073000e+02 6.004000e+02 +15 7897 -1.603700e+02 4.775300e+02 +19 7897 -9.226000e+02 7.073400e+02 +4 7898 -2.433900e+02 6.052400e+02 +19 7898 3.139001e+01 7.880800e+02 +4 7899 -2.433900e+02 6.052400e+02 +15 7899 4.705699e+02 4.993101e+02 +4 7900 -1.384900e+02 6.088900e+02 +15 7900 5.932500e+02 5.070601e+02 +4 7901 -6.080100e+02 6.153400e+02 +15 7901 5.871997e+01 5.004000e+02 +4 7902 7.189001e+01 6.244900e+02 +16 7902 -3.922300e+02 6.633700e+02 +4 7903 -3.216000e+02 6.249200e+02 +15 7903 3.803500e+02 5.193600e+02 +4 7904 -5.818005e+01 6.313201e+02 +15 7904 6.842200e+02 5.336899e+02 +19 7904 3.736300e+02 8.557600e+02 +4 7905 -2.496600e+02 6.339299e+02 +16 7905 -7.486900e+02 6.863800e+02 +4 7906 -1.811400e+02 6.488500e+02 +15 7906 5.437000e+02 5.500900e+02 +4 7907 -1.302600e+03 6.519800e+02 +15 7907 -6.085200e+02 5.366500e+02 +4 7908 -6.672998e+01 6.539399e+02 +16 7908 -5.401300e+02 6.999500e+02 +19 7908 3.561700e+02 8.887200e+02 +4 7909 -1.396300e+03 6.574399e+02 +15 7909 -6.984400e+02 5.402900e+02 +4 7910 -5.412200e+02 6.859100e+02 +15 7910 1.239600e+02 5.753600e+02 +4 7911 -6.000600e+02 6.909500e+02 +19 7911 -5.918500e+02 8.968300e+02 +4 7912 -1.620400e+02 7.330500e+02 +15 7912 5.625300e+02 6.428600e+02 +5 7913 -9.718400e+02 9.101600e+02 +15 7913 6.164500e+02 5.149500e+02 +16 7913 -5.943700e+02 6.610200e+02 +5 7914 -1.210640e+03 5.085800e+02 +19 7914 -1.461700e+02 3.348101e+02 +5 7915 8.806599e+02 7.155400e+02 +16 7915 6.564301e+02 3.249100e+02 +5 7916 -9.297100e+02 7.607300e+02 +10 7916 -1.435440e+03 -7.133997e+01 +15 7916 6.317100e+02 3.913600e+02 +19 7916 2.861500e+02 6.201700e+02 +5 7917 -9.523600e+02 9.466500e+02 +10 7917 -1.422430e+03 1.191200e+02 +15 7917 6.340601e+02 5.401799e+02 +16 7917 -5.748900e+02 6.854800e+02 +5 7918 -1.182750e+03 3.543301e+02 +19 7918 -1.495800e+02 1.230000e+02 +5 7919 -9.727900e+02 4.274199e+02 +14 7919 -2.408700e+02 2.264300e+02 +5 7920 -1.188970e+03 4.318700e+02 +19 7920 -1.368400e+02 2.292200e+02 +5 7921 -1.098590e+03 6.343201e+02 +15 7921 4.732800e+02 3.108900e+02 +16 7921 -7.279800e+02 4.612800e+02 +19 7921 3.238000e+01 4.801100e+02 +5 7922 -1.247650e+03 8.883101e+02 +14 7922 -3.652200e+02 5.477200e+02 +5 7923 -9.530800e+02 3.188301e+02 +14 7923 -2.468700e+02 1.541800e+02 +5 7924 -9.988200e+02 3.640300e+02 +15 7924 5.168199e+02 8.439001e+01 +16 7924 -6.699700e+02 2.380100e+02 +5 7925 -1.244440e+03 4.324399e+02 +19 7925 -2.081600e+02 2.409900e+02 +5 7926 -1.203490e+03 4.393900e+02 +19 7926 -1.514301e+02 2.435601e+02 +5 7927 -8.678500e+02 8.988000e+02 +20 7927 -1.236660e+03 1.385100e+02 +5 7928 -1.225180e+03 4.385300e+02 +19 7928 -1.816801e+02 2.455901e+02 +5 7929 -8.604500e+02 9.071600e+02 +19 7929 4.078101e+02 7.993700e+02 +5 7930 -8.740200e+02 9.073700e+02 +19 7930 3.904600e+02 8.036500e+02 +5 7931 -1.007860e+03 9.442000e+02 +19 7931 2.254000e+02 8.690300e+02 +5 7932 -1.077030e+03 3.286599e+02 +14 7932 -3.102100e+02 1.759300e+02 +5 7933 -9.410700e+02 3.522700e+02 +14 7933 -2.324700e+02 1.749500e+02 +5 7934 -1.175780e+03 4.260100e+02 +19 7934 -1.206801e+02 2.203500e+02 +5 7935 -1.060560e+03 4.770300e+02 +15 7935 4.779900e+02 1.824200e+02 +19 7935 4.091003e+01 2.666200e+02 +5 7936 -1.060560e+03 4.770300e+02 +19 7936 4.091003e+01 2.666200e+02 +5 7937 8.265500e+02 7.729700e+02 +16 7937 6.340000e+02 3.691600e+02 +5 7938 -1.264840e+03 8.270200e+02 +16 7938 -8.493600e+02 6.350300e+02 +19 7938 -1.351300e+02 7.492500e+02 +5 7939 -1.104870e+03 8.412300e+02 +15 7939 5.019700e+02 4.721500e+02 +16 7939 -7.040300e+02 6.233101e+02 +5 7940 -9.770400e+02 8.500500e+02 +14 7940 -1.886900e+02 4.900900e+02 +16 7940 -5.997900e+02 6.135200e+02 +5 7941 -8.962100e+02 8.602800e+02 +10 7941 -1.375260e+03 1.888000e+01 +14 7941 -1.385100e+02 4.847300e+02 +15 7941 6.727100e+02 4.667900e+02 +16 7941 -5.365600e+02 6.115701e+02 +5 7942 -8.613900e+02 8.637800e+02 +7 7942 -9.684600e+02 7.435000e+02 +10 7942 -1.342870e+03 1.343994e+01 +14 7942 -1.185100e+02 4.817000e+02 +15 7942 6.983700e+02 4.660800e+02 +16 7942 -5.111200e+02 6.100300e+02 +19 7942 3.978101e+02 7.435701e+02 +5 7943 -1.134730e+03 9.098199e+02 +15 7943 4.860200e+02 5.275900e+02 +5 7944 -8.960900e+02 9.594900e+02 +15 7944 6.839100e+02 5.454200e+02 +16 7944 -5.274900e+02 6.877900e+02 +5 7945 -1.243550e+03 4.421400e+02 +19 7945 -2.056100e+02 2.531200e+02 +5 7946 -1.089300e+03 4.855000e+02 +19 7946 7.550049e+00 2.830500e+02 +5 7947 -1.080560e+03 4.870100e+02 +14 7947 -3.083600e+02 2.769300e+02 +15 7947 4.639301e+02 1.928800e+02 +19 7947 1.790002e+01 2.836000e+02 +5 7948 -8.734300e+02 5.090701e+02 +15 7948 6.400900e+02 1.844400e+02 +19 7948 3.026000e+02 2.757600e+02 +5 7949 -8.734300e+02 5.090701e+02 +15 7949 6.400900e+02 1.844400e+02 +19 7949 3.026000e+02 2.757600e+02 +5 7950 -9.346300e+02 5.368000e+02 +19 7950 2.290500e+02 3.244500e+02 +5 7951 -1.268070e+03 6.078101e+02 +15 7951 3.304800e+02 3.096500e+02 +5 7952 -1.136810e+03 7.650900e+02 +15 7952 4.630699e+02 4.164500e+02 +5 7953 -1.267890e+03 7.897000e+02 +16 7953 -8.558700e+02 6.057500e+02 +19 7953 -1.484900e+02 7.021500e+02 +5 7954 -1.104520e+03 8.480800e+02 +14 7954 -2.735100e+02 5.055300e+02 +19 7954 7.768005e+01 7.578300e+02 +5 7955 -1.053420e+03 3.727000e+02 +19 7955 2.498999e+01 1.254700e+02 +5 7956 -1.023170e+03 3.891300e+02 +16 7956 -6.926700e+02 2.616000e+02 +5 7957 -1.170530e+03 4.328900e+02 +19 7957 -1.124900e+02 2.294500e+02 +5 7958 -1.125600e+03 6.714299e+02 +14 7958 -3.133400e+02 3.985701e+02 +5 7959 -9.741200e+02 6.858300e+02 +15 7959 5.854700e+02 3.369399e+02 +5 7960 -1.157150e+03 8.084200e+02 +14 7960 -3.144100e+02 4.873700e+02 +15 7960 4.516600e+02 4.520800e+02 +16 7960 -7.562000e+02 6.049200e+02 +5 7961 -1.001070e+03 8.383400e+02 +14 7961 -2.049100e+02 4.862700e+02 +15 7961 5.860800e+02 4.595000e+02 +16 7961 -6.203500e+02 6.074399e+02 +19 7961 2.122900e+02 7.330800e+02 +5 7962 -1.001070e+03 8.383400e+02 +16 7962 -6.203500e+02 6.074399e+02 +19 7962 2.122900e+02 7.330800e+02 +5 7963 -1.122710e+03 9.245200e+02 +14 7963 -2.753000e+02 5.549900e+02 +15 7963 4.972000e+02 5.381200e+02 +20 7963 -1.445610e+03 2.114900e+02 +5 7964 -1.122710e+03 9.245200e+02 +14 7964 -2.753000e+02 5.549900e+02 +15 7964 4.972000e+02 5.381200e+02 +20 7964 -1.445610e+03 2.114900e+02 +5 7965 -9.500500e+02 9.364399e+02 +10 7965 -1.423340e+03 1.089600e+02 +15 7965 6.345900e+02 5.321600e+02 +19 7965 2.943900e+02 8.498900e+02 +5 7966 -1.017510e+03 9.433500e+02 +19 7966 2.120601e+02 8.682600e+02 +5 7967 -1.045180e+03 9.517600e+02 +14 7967 -2.194100e+02 5.619200e+02 +19 7967 1.800699e+02 8.852000e+02 +20 7967 -1.364180e+03 2.129000e+02 +5 7968 -1.116710e+03 4.599399e+02 +19 7968 -3.688000e+01 2.543201e+02 +5 7969 -1.122920e+03 7.260800e+02 +15 7969 4.675699e+02 3.850100e+02 +5 7970 -1.245880e+03 8.355300e+02 +14 7970 -3.704100e+02 5.160200e+02 +16 7970 -8.300200e+02 6.383900e+02 +19 7970 -1.081801e+02 7.589500e+02 +5 7971 -1.154440e+03 8.938800e+02 +19 7971 2.307996e+01 8.216400e+02 +5 7972 -1.117470e+03 9.210400e+02 +15 7972 5.007100e+02 5.352800e+02 +5 7973 -1.004400e+03 4.802700e+02 +15 7973 5.291000e+02 1.769800e+02 +5 7974 -1.072860e+03 8.455300e+02 +16 7974 -6.799800e+02 6.226400e+02 +19 7974 1.176899e+02 7.521400e+02 +5 7975 -1.047400e+03 9.394301e+02 +19 7975 1.739000e+02 8.693500e+02 +6 7976 8.068800e+02 -1.009003e+01 +17 7976 -1.009650e+03 3.799500e+02 +6 7977 9.708997e+01 1.285999e+01 +16 7977 6.492100e+02 4.104900e+02 +6 7978 4.199200e+02 -2.863000e+02 +13 7978 -7.675400e+02 2.203003e+01 +16 7978 8.774100e+02 2.787100e+02 +6 7979 4.128400e+02 -2.855000e+02 +13 7979 -7.879600e+02 2.509998e+01 +18 7979 -2.925200e+02 -1.608997e+01 +6 7980 8.254200e+02 1.293100e+02 +17 7980 -9.870200e+02 5.434399e+02 +6 7981 4.782100e+02 -2.295600e+02 +10 7981 6.599976e+00 -4.073800e+02 +20 7981 -2.349399e+02 -1.460400e+02 +6 7982 4.150100e+02 -2.973100e+02 +13 7982 -7.808200e+02 -1.954004e+01 +6 7983 4.279000e+02 -2.932900e+02 +13 7983 -7.414300e+02 1.109985e+00 +6 7984 2.168600e+02 -3.453003e+01 +13 7984 -9.612500e+02 6.113401e+02 +7 7985 1.170110e+03 5.820300e+02 +12 7985 -6.310059e+00 -2.720601e+02 +7 7986 -4.799000e+02 6.217200e+02 +16 7986 -8.732001e+01 5.350701e+02 +18 7986 -1.137940e+03 2.864299e+02 +7 7987 -3.968101e+02 6.833900e+02 +16 7987 -3.101001e+01 5.841600e+02 +7 7988 -1.064190e+03 8.703500e+02 +10 7988 -1.424070e+03 1.329000e+02 +7 7989 -2.693300e+02 5.360701e+02 +14 7989 2.839400e+02 3.273800e+02 +18 7989 -9.379100e+02 1.962700e+02 +20 7989 -7.989600e+02 -2.619995e+01 +7 7990 -1.172770e+03 8.397800e+02 +16 7990 -6.582800e+02 6.706100e+02 +7 7991 -9.780600e+02 2.921500e+02 +14 7991 -1.348400e+02 2.184500e+02 +16 7991 -5.100800e+02 2.852900e+02 +7 7992 9.799700e+02 3.862300e+02 +12 7992 -1.551000e+02 -4.668300e+02 +17 7992 -9.296400e+02 5.646699e+02 +7 7993 9.471799e+02 4.662900e+02 +12 7993 -1.947200e+02 -3.826700e+02 +7 7994 -3.105100e+02 5.859600e+02 +16 7994 3.113000e+01 5.171700e+02 +7 7995 -7.983000e+02 6.775900e+02 +14 7995 -1.795999e+01 4.363201e+02 +16 7995 -3.759600e+02 5.682400e+02 +19 7995 6.365200e+02 6.704100e+02 +7 7996 -1.248230e+03 9.596100e+02 +10 7996 -1.600430e+03 2.250300e+02 +15 7996 5.033600e+02 5.969200e+02 +7 7997 1.198880e+03 2.241699e+02 +12 7997 4.312000e+01 -6.106300e+02 +18 7997 2.398199e+02 -7.648999e+01 +20 7997 2.125300e+02 -2.605200e+02 +7 7998 9.775300e+02 3.010901e+02 +12 7998 -1.563101e+02 -5.440100e+02 +17 7998 -9.289800e+02 3.619199e+02 +7 7999 -9.807400e+02 3.915801e+02 +15 7999 6.868800e+02 2.015400e+02 +16 7999 -5.132000e+02 3.559000e+02 +7 8000 -9.167200e+02 5.810400e+02 +14 8000 -9.404001e+01 3.856600e+02 +7 8001 -1.159640e+03 6.041700e+02 +14 8001 -2.295400e+02 4.018400e+02 +15 8001 5.592900e+02 3.527500e+02 +16 8001 -6.444100e+02 5.024200e+02 +19 8001 1.689800e+02 5.535801e+02 +7 8002 -7.900200e+02 6.358400e+02 +14 8002 -1.423001e+01 4.120400e+02 +7 8003 4.663600e+02 6.403600e+02 +12 8003 -5.093500e+02 -3.373199e+02 +16 8003 4.112700e+02 5.956700e+02 +7 8004 -1.285380e+03 6.775601e+02 +15 8004 4.709500e+02 3.987700e+02 +19 8004 2.727002e+01 6.256400e+02 +7 8005 -1.296970e+03 9.097900e+02 +10 8005 -1.640900e+03 1.915000e+02 +7 8006 -1.015150e+03 2.796799e+02 +14 8006 -1.565300e+02 2.128500e+02 +16 8006 -5.364400e+02 2.780900e+02 +7 8007 -1.015150e+03 2.796799e+02 +14 8007 -1.565300e+02 2.128500e+02 +16 8007 -5.364400e+02 2.780900e+02 +7 8008 -9.817000e+02 3.380601e+02 +15 8008 6.845601e+02 1.615900e+02 +7 8009 -7.949000e+02 3.790300e+02 +14 8009 -2.239001e+01 2.635300e+02 +15 8009 8.441100e+02 1.951800e+02 +16 8009 -3.679800e+02 3.511300e+02 +7 8010 -1.067490e+03 3.950801e+02 +16 8010 -5.741100e+02 3.536799e+02 +7 8011 -1.067490e+03 3.950801e+02 +16 8011 -5.741100e+02 3.536799e+02 +7 8012 1.164050e+03 4.433500e+02 +12 8012 7.689941e+00 -4.113400e+02 +7 8013 1.092260e+03 4.715500e+02 +12 8013 -6.418005e+01 -3.820601e+02 +7 8014 -7.129600e+02 4.923401e+02 +10 8014 -1.140390e+03 -2.307600e+02 +16 8014 -2.931200e+02 4.320300e+02 +7 8015 1.039000e+03 4.996400e+02 +12 8015 -1.120000e+02 -3.410000e+02 +7 8016 -4.610999e+01 5.252800e+02 +16 8016 2.019301e+02 4.795100e+02 +7 8017 5.262200e+02 6.371000e+02 +16 8017 4.529399e+02 5.974200e+02 +7 8018 -8.759500e+02 6.834800e+02 +10 8018 -1.260340e+03 -4.723999e+01 +16 8018 -4.391300e+02 5.698201e+02 +20 8018 -1.173260e+03 6.584009e+01 +7 8019 -1.135820e+03 8.576500e+02 +10 8019 -1.494130e+03 1.262100e+02 +14 8019 -2.116500e+02 5.482600e+02 +16 8019 -6.335000e+02 6.873600e+02 +7 8020 -9.052800e+02 2.739299e+02 +16 8020 -4.544300e+02 2.735000e+02 +7 8021 -9.052800e+02 2.739299e+02 +14 8021 -9.214999e+01 2.039500e+02 +7 8022 -7.982100e+02 2.824099e+02 +14 8022 -2.723001e+01 2.073500e+02 +16 8022 -3.710500e+02 2.836899e+02 +7 8023 1.009530e+03 2.998800e+02 +13 8023 1.249900e+03 2.880500e+02 +17 8023 -7.148199e+02 3.626500e+02 +7 8024 9.473601e+02 2.981799e+02 +17 8024 -8.626000e+02 3.597700e+02 +20 8024 5.977002e+01 -2.148400e+02 +7 8025 1.213790e+03 3.531200e+02 +12 8025 5.210999e+01 -4.978000e+02 +18 8025 2.494600e+02 1.566003e+01 +7 8026 1.122600e+03 3.524700e+02 +20 8026 1.659000e+02 -1.797900e+02 +7 8027 -9.074800e+02 3.850000e+02 +16 8027 -5.402700e+02 3.553600e+02 +7 8028 -6.865000e+02 4.647500e+02 +16 8028 -2.703300e+02 4.163600e+02 +7 8029 1.062220e+03 4.775500e+02 +12 8029 -8.794995e+01 -3.709000e+02 +7 8030 9.670901e+02 5.182300e+02 +12 8030 -1.799500e+02 -3.267700e+02 +17 8030 -1.094890e+03 8.751400e+02 +7 8031 -5.082900e+02 5.254900e+02 +19 8031 1.135770e+03 4.451400e+02 +7 8032 -1.959399e+02 5.669299e+02 +14 8032 3.306200e+02 3.494700e+02 +16 8032 1.007100e+02 5.067100e+02 +7 8033 -1.070290e+03 5.924700e+02 +16 8033 -7.999800e+02 4.897700e+02 +7 8034 -1.521801e+02 6.147000e+02 +12 8034 -1.291590e+03 -2.007100e+02 +7 8035 -4.387100e+02 6.493800e+02 +16 8035 -5.746002e+01 5.607400e+02 +18 8035 -1.103310e+03 3.045400e+02 +19 8035 1.230350e+03 6.100701e+02 +7 8036 -8.890100e+02 7.417200e+02 +16 8036 -4.508400e+02 6.106100e+02 +7 8037 -1.234700e+03 7.440601e+02 +14 8037 -2.690300e+02 4.819000e+02 +15 8037 5.074301e+02 4.478700e+02 +7 8038 -1.002840e+03 7.807300e+02 +16 8038 -5.365900e+02 6.346801e+02 +7 8039 -1.002840e+03 7.807300e+02 +16 8039 -5.365900e+02 6.346801e+02 +7 8040 -1.249170e+03 8.069600e+02 +10 8040 -1.614000e+03 8.541003e+01 +16 8040 -7.095200e+02 6.432500e+02 +20 8040 -1.446700e+03 1.626000e+02 +7 8041 -1.364300e+03 8.229900e+02 +16 8041 -7.846100e+02 6.494800e+02 +7 8042 -1.149410e+03 1.979199e+02 +14 8042 -3.560300e+02 2.227300e+02 +15 8042 3.896100e+02 5.788000e+01 +16 8042 -7.864200e+02 2.084800e+02 +7 8043 -1.149410e+03 1.979199e+02 +15 8043 3.896100e+02 5.788000e+01 +16 8043 -7.864200e+02 2.084800e+02 +7 8044 1.140350e+03 2.142500e+02 +12 8044 -8.949951e+00 -6.251500e+02 +7 8045 -8.585400e+02 2.150000e+02 +15 8045 7.803300e+02 6.854999e+01 +7 8046 -9.816100e+02 2.162500e+02 +16 8046 -5.127700e+02 2.297600e+02 +7 8047 -1.035540e+03 2.611899e+02 +14 8047 -1.691500e+02 2.015000e+02 +16 8047 -5.511000e+02 2.618800e+02 +7 8048 -8.195000e+02 3.071699e+02 +16 8048 -3.885200e+02 2.982500e+02 +7 8049 -9.690900e+02 3.121599e+02 +14 8049 -1.299300e+02 2.298900e+02 +16 8049 -5.038700e+02 2.980601e+02 +7 8050 -1.004170e+03 3.313500e+02 +14 8050 -1.489000e+02 2.425500e+02 +16 8050 -5.305300e+02 3.117400e+02 +7 8051 -1.097730e+03 3.473900e+02 +16 8051 -5.984400e+02 3.209100e+02 +7 8052 9.315000e+02 3.712000e+02 +12 8052 -1.988900e+02 -4.779500e+02 +7 8053 1.026210e+03 3.727800e+02 +12 8053 -1.134301e+02 -4.779800e+02 +17 8053 -6.779900e+02 5.352100e+02 +7 8054 -8.203900e+02 3.753401e+02 +10 8054 -1.231110e+03 -3.401000e+02 +14 8054 -3.839001e+01 2.630800e+02 +16 8054 -3.903100e+02 3.494600e+02 +7 8055 -8.527200e+02 3.789000e+02 +10 8055 -1.260170e+03 -3.354200e+02 +14 8055 -5.775000e+01 2.667700e+02 +16 8055 -4.154400e+02 3.500000e+02 +7 8056 -7.454100e+02 3.986200e+02 +14 8056 7.279999e+00 2.713700e+02 +19 8056 7.174600e+02 3.129900e+02 +7 8057 -8.215500e+02 4.027600e+02 +10 8057 -1.230050e+03 -3.115699e+02 +14 8057 -3.854001e+01 2.784300e+02 +16 8057 -3.915000e+02 3.701500e+02 +7 8058 -8.215500e+02 4.027600e+02 +10 8058 -1.230050e+03 -3.115699e+02 +14 8058 -3.817001e+01 2.764400e+02 +16 8058 -3.915000e+02 3.701500e+02 +7 8059 9.892700e+02 4.197300e+02 +17 8059 -7.576000e+02 6.456799e+02 +7 8060 9.193401e+02 4.353800e+02 +12 8060 -2.096100e+02 -4.168700e+02 +7 8061 9.193401e+02 4.353800e+02 +12 8061 -2.096100e+02 -4.168700e+02 +7 8062 9.765801e+02 4.375601e+02 +12 8062 -1.578199e+02 -4.172800e+02 +18 8062 8.329004e+01 8.053003e+01 +20 8062 7.608997e+01 -1.260200e+02 +7 8063 -8.325900e+02 4.531699e+02 +10 8063 -1.235640e+03 -2.651200e+02 +11 8063 -9.418100e+02 2.711700e+02 +16 8063 -4.000900e+02 4.047300e+02 +18 8063 -1.341800e+03 1.159299e+02 +20 8063 -1.154150e+03 -1.006000e+02 +7 8064 -5.822700e+02 4.845601e+02 +14 8064 1.047900e+02 2.923700e+02 +16 8064 -1.550400e+02 4.339000e+02 +19 8064 1.054080e+03 3.775601e+02 +7 8065 -1.090830e+03 4.862100e+02 +19 8065 2.436100e+02 4.163500e+02 +7 8066 -5.828600e+02 5.053800e+02 +10 8066 -1.060870e+03 -2.247200e+02 +14 8066 1.049600e+02 3.033000e+02 +7 8067 -7.478003e+01 5.848400e+02 +18 8067 -7.564800e+02 2.255300e+02 +7 8068 -1.186260e+03 6.008400e+02 +10 8068 -1.570450e+03 -1.129800e+02 +16 8068 -6.629000e+02 4.975100e+02 +7 8069 -1.186260e+03 6.008400e+02 +10 8069 -1.570450e+03 -1.129800e+02 +14 8069 -2.449300e+02 4.000300e+02 +15 8069 5.398900e+02 3.488000e+02 +16 8069 -6.629000e+02 4.975100e+02 +19 8069 1.384600e+02 5.455200e+02 +7 8070 -1.233540e+03 6.070601e+02 +10 8070 -1.618790e+03 -1.055900e+02 +14 8070 -2.703600e+02 4.042500e+02 +15 8070 5.085300e+02 3.509299e+02 +16 8070 -6.949100e+02 5.023400e+02 +19 8070 8.852002e+01 5.500000e+02 +7 8071 -1.233540e+03 6.070601e+02 +10 8071 -1.618790e+03 -1.055900e+02 +14 8071 -2.703600e+02 4.042500e+02 +15 8071 5.085300e+02 3.509299e+02 +16 8071 -6.949100e+02 5.023400e+02 +19 8071 8.852002e+01 5.500000e+02 +7 8072 -3.069946e+00 6.191200e+02 +16 8072 2.491899e+02 5.532400e+02 +7 8073 -1.255880e+03 6.388500e+02 +14 8073 -2.829800e+02 4.211799e+02 +19 8073 6.320996e+01 5.840900e+02 +7 8074 -7.553700e+02 7.243300e+02 +11 8074 -9.042900e+02 6.340601e+02 +7 8075 -1.334580e+03 7.499200e+02 +19 8075 -1.653003e+01 7.020900e+02 +7 8076 -8.417100e+02 7.549600e+02 +10 8076 -1.225510e+03 1.807996e+01 +16 8076 -4.123600e+02 6.233600e+02 +7 8077 -8.508300e+02 8.011200e+02 +10 8077 -1.232000e+03 6.018005e+01 +16 8077 -4.165800e+02 6.550400e+02 +19 8077 5.678700e+02 8.155000e+02 +7 8078 -8.840500e+02 8.099600e+02 +15 8078 7.681500e+02 5.223000e+02 +16 8078 -4.467000e+02 6.609900e+02 +19 8078 5.117900e+02 8.325200e+02 +7 8079 -1.042870e+03 8.171899e+02 +10 8079 -1.407750e+03 8.384998e+01 +14 8079 -1.568500e+02 5.225200e+02 +7 8080 -1.249250e+03 8.331000e+02 +10 8080 -1.611560e+03 1.106200e+02 +15 8080 4.990900e+02 5.102600e+02 +16 8080 -7.095000e+02 6.632500e+02 +19 8080 7.558997e+01 8.121700e+02 +20 8080 -1.446350e+03 1.826799e+02 +7 8081 -1.320830e+03 8.673400e+02 +15 8081 4.529399e+02 5.284100e+02 +7 8082 -7.539000e+02 2.286200e+02 +16 8082 -3.587500e+02 2.432300e+02 +7 8083 -8.428800e+02 2.308800e+02 +16 8083 -4.076500e+02 2.425600e+02 +7 8084 -8.964400e+02 2.318900e+02 +14 8084 -8.879999e+01 1.807400e+02 +15 8084 7.497600e+02 8.128998e+01 +16 8084 -4.478700e+02 2.422900e+02 +7 8085 -1.090630e+03 2.326699e+02 +16 8085 -5.916800e+02 2.391300e+02 +7 8086 8.931899e+02 2.429099e+02 +16 8086 9.571100e+02 2.811000e+02 +7 8087 -8.149600e+02 2.525901e+02 +10 8087 -1.233070e+03 -4.583199e+02 +14 8087 -3.878000e+01 1.897900e+02 +15 8087 8.218199e+02 9.756000e+01 +16 8087 -3.850300e+02 2.601400e+02 +7 8088 -2.197998e+01 3.018301e+02 +16 8088 2.061500e+02 3.131899e+02 +7 8089 5.113000e+02 3.374800e+02 +16 8089 4.373400e+02 3.511000e+02 +7 8090 5.113000e+02 3.374800e+02 +16 8090 4.373400e+02 3.511000e+02 +7 8091 -8.600900e+02 3.403401e+02 +16 8091 -4.224000e+02 3.217500e+02 +7 8092 8.379500e+02 3.591799e+02 +16 8092 9.216700e+02 3.713600e+02 +7 8093 -4.467004e+01 3.704600e+02 +16 8093 1.920601e+02 3.640500e+02 +7 8094 -4.759100e+02 3.737000e+02 +14 8094 1.603000e+02 2.359900e+02 +7 8095 -9.978700e+02 3.813700e+02 +16 8095 -5.261200e+02 3.477300e+02 +7 8096 -7.921600e+02 4.198700e+02 +10 8096 -1.201510e+03 -2.986801e+02 +14 8096 -2.092999e+01 2.863500e+02 +15 8096 8.435500e+02 2.272100e+02 +16 8096 -3.691400e+02 3.820400e+02 +19 8096 6.408401e+02 3.433000e+02 +7 8097 8.706201e+02 4.283800e+02 +12 8097 -2.585500e+02 -4.202100e+02 +7 8098 -6.456200e+02 4.286000e+02 +16 8098 -2.137900e+02 3.882900e+02 +7 8099 1.310860e+03 4.341500e+02 +20 8099 2.653000e+02 -1.295000e+02 +7 8100 4.565000e+02 4.306000e+02 +18 8100 -9.102002e+01 3.050049e+00 +20 8100 -6.482996e+01 -1.949100e+02 +7 8101 -6.135600e+02 4.330000e+02 +14 8101 8.734998e+01 2.635800e+02 +16 8101 -1.737900e+02 3.960400e+02 +19 8101 1.021520e+03 3.087700e+02 +7 8102 -5.814900e+02 4.383600e+02 +10 8102 -1.062780e+03 -2.869000e+02 +14 8102 1.045600e+02 2.677700e+02 +16 8102 -1.540700e+02 4.014900e+02 +18 8102 -1.248780e+03 1.313401e+02 +19 8102 1.055550e+03 3.203101e+02 +20 8102 -1.075830e+03 -8.656995e+01 +7 8103 9.797500e+02 4.536899e+02 +12 8103 -1.614600e+02 -4.018600e+02 +7 8104 9.271997e+01 4.557200e+02 +16 8104 3.061801e+02 4.324100e+02 +7 8105 1.303340e+03 4.733700e+02 +12 8105 1.242000e+02 -3.768000e+02 +7 8106 -7.713000e+02 4.854299e+02 +10 8106 -1.181880e+03 -2.349500e+02 +14 8106 -6.250000e+00 3.223300e+02 +19 8106 6.787600e+02 4.222100e+02 +7 8107 -8.218200e+02 4.963101e+02 +10 8107 -1.224630e+03 -2.232700e+02 +11 8107 -9.372000e+02 3.319000e+02 +20 8107 -1.148350e+03 -6.687000e+01 +7 8108 -8.218200e+02 4.963101e+02 +10 8108 -1.224630e+03 -2.232700e+02 +11 8108 -9.372000e+02 3.319000e+02 +20 8108 -1.148350e+03 -6.687000e+01 +7 8109 -3.635500e+02 5.071500e+02 +16 8109 -1.191998e+01 4.578201e+02 +19 8109 1.316570e+03 4.489800e+02 +7 8110 -7.474100e+02 5.092600e+02 +16 8110 -3.315600e+02 4.476300e+02 +19 8110 7.147100e+02 4.551100e+02 +7 8111 -8.599500e+02 5.166599e+02 +10 8111 -1.257720e+03 -2.036400e+02 +11 8111 -9.745800e+02 3.525400e+02 +14 8111 -5.973001e+01 3.465800e+02 +16 8111 -4.246100e+02 4.494399e+02 +18 8111 -1.361850e+03 1.692500e+02 +19 8111 5.420500e+02 4.691400e+02 +20 8111 -1.170410e+03 -5.480005e+01 +7 8112 -4.241500e+02 5.269299e+02 +14 8112 1.923900e+02 3.203900e+02 +19 8112 1.238340e+03 4.605801e+02 +7 8113 1.782996e+01 5.423600e+02 +16 8113 2.497600e+02 4.979800e+02 +7 8114 -6.108900e+02 5.524000e+02 +14 8114 9.116998e+01 3.235200e+02 +7 8115 -8.359200e+02 5.618500e+02 +14 8115 -4.364999e+01 3.701600e+02 +7 8116 -8.359200e+02 5.618500e+02 +14 8116 -4.364999e+01 3.701600e+02 +19 8116 5.786500e+02 5.233700e+02 +7 8117 -8.357800e+02 5.971100e+02 +14 8117 -4.235001e+01 3.913500e+02 +19 8117 5.797600e+02 5.680601e+02 +7 8118 -3.757900e+02 5.978900e+02 +14 8118 2.203400e+02 3.580700e+02 +16 8118 -1.650000e+01 5.241500e+02 +19 8118 1.305930e+03 5.570000e+02 +7 8119 -9.116900e+02 5.997400e+02 +14 8119 -8.800000e+01 3.965100e+02 +15 8119 7.440100e+02 3.615300e+02 +7 8120 -5.284500e+02 6.002600e+02 +16 8120 -1.216700e+02 5.216799e+02 +7 8121 -9.537500e+02 6.044700e+02 +15 8121 7.107500e+02 3.626799e+02 +7 8122 4.006995e+01 6.118400e+02 +16 8122 2.795699e+02 5.495601e+02 +7 8123 -8.093100e+02 6.187400e+02 +10 8123 -1.207110e+03 -1.098700e+02 +14 8123 -2.700000e+01 4.032000e+02 +7 8124 -1.160610e+03 6.527100e+02 +16 8124 -6.469200e+02 5.369600e+02 +19 8124 1.662900e+02 6.123300e+02 +7 8125 -1.182290e+03 6.535400e+02 +19 8125 1.420500e+02 6.104299e+02 +7 8126 -1.202430e+03 6.539600e+02 +19 8126 1.205000e+02 6.082800e+02 +7 8127 -1.222140e+03 6.545300e+02 +19 8127 9.926001e+01 6.063600e+02 +7 8128 -1.243270e+03 6.541700e+02 +19 8128 7.683997e+01 6.037100e+02 +7 8129 -1.263210e+03 6.545100e+02 +16 8129 -7.161100e+02 5.341899e+02 +19 8129 5.562000e+01 6.014299e+02 +7 8130 -8.550800e+02 6.967900e+02 +14 8130 -5.141000e+01 4.510100e+02 +7 8131 -7.770400e+02 7.341799e+02 +19 8131 6.712000e+02 7.409900e+02 +7 8132 -7.980700e+02 7.398101e+02 +10 8132 -1.188810e+03 1.709961e+00 +7 8133 -8.688700e+02 7.784500e+02 +14 8133 -5.695001e+01 4.977100e+02 +7 8134 -8.483600e+02 7.784100e+02 +16 8134 -4.136900e+02 6.388000e+02 +7 8135 -9.332100e+02 8.001400e+02 +15 8135 7.324700e+02 5.107100e+02 +16 8135 -4.794800e+02 6.517300e+02 +7 8136 -9.737100e+02 8.053700e+02 +16 8136 -5.128200e+02 6.544800e+02 +7 8137 -1.114010e+03 9.749800e+02 +14 8137 -1.878700e+02 5.994399e+02 +15 8137 6.103400e+02 6.203900e+02 +7 8138 1.312400e+02 6.465991e+01 +20 8138 -2.288900e+02 -4.176600e+02 +7 8139 -1.156550e+03 1.585200e+02 +14 8139 -3.665800e+02 1.911300e+02 +15 8139 3.791200e+02 2.885999e+01 +16 8139 -7.951400e+02 1.787800e+02 +7 8140 3.393005e+01 1.638401e+02 +16 8140 1.944995e+01 2.009200e+02 +7 8141 1.084290e+03 1.711899e+02 +20 8141 1.482500e+02 -2.962800e+02 +7 8142 -2.009998e+01 1.965100e+02 +16 8142 2.116500e+02 2.326700e+02 +7 8143 4.485900e+02 2.226300e+02 +12 8143 -5.254400e+02 -6.966899e+02 +13 8143 3.106000e+02 1.323101e+02 +16 8143 3.882100e+02 2.554400e+02 +20 8143 -6.803003e+01 -3.166600e+02 +7 8144 8.905005e+01 2.258900e+02 +16 8144 3.057200e+02 2.569800e+02 +7 8145 -8.235600e+02 2.321699e+02 +14 8145 -4.522000e+01 1.793000e+02 +7 8146 -7.821700e+02 2.510601e+02 +10 8146 -1.203340e+03 -4.607100e+02 +7 8147 -1.068140e+03 2.551500e+02 +16 8147 -5.741100e+02 2.558100e+02 +7 8148 5.817400e+02 2.709600e+02 +16 8148 4.943800e+02 2.976100e+02 +18 8148 -4.329956e+00 -1.067200e+02 +7 8149 -7.795800e+02 3.216799e+02 +15 8149 8.530800e+02 1.516500e+02 +16 8149 -3.573100e+02 3.103900e+02 +19 8149 6.593000e+02 2.150701e+02 +7 8150 1.365130e+03 3.290100e+02 +12 8150 1.838101e+02 -5.119100e+02 +7 8151 9.038000e+01 3.330400e+02 +16 8151 3.059800e+02 3.381799e+02 +7 8152 -1.090970e+03 3.343201e+02 +16 8152 -5.927900e+02 3.116300e+02 +19 8152 2.398000e+02 2.302200e+02 +7 8153 9.466699e+02 3.381300e+02 +18 8153 6.147998e+01 6.390015e+00 +7 8154 -8.722400e+02 3.538101e+02 +14 8154 -7.156000e+01 2.518300e+02 +15 8154 7.709600e+02 1.753900e+02 +16 8154 -4.322400e+02 3.311200e+02 +7 8155 -1.021220e+03 3.577000e+02 +14 8155 -1.582900e+02 2.580900e+02 +19 8155 3.258400e+02 2.618201e+02 +7 8156 -7.814800e+02 3.709199e+02 +10 8156 -1.195650e+03 -3.450900e+02 +14 8156 -1.460001e+01 2.578600e+02 +16 8156 -3.582900e+02 3.468700e+02 +19 8156 6.586699e+02 2.808101e+02 +7 8157 -7.442300e+02 4.241599e+02 +14 8157 8.220001e+00 2.858400e+02 +7 8158 -9.276400e+02 4.465400e+02 +15 8158 7.288199e+02 2.453100e+02 +16 8158 -4.752400e+02 3.969000e+02 +7 8159 7.756006e+01 4.508600e+02 +16 8159 2.937300e+02 4.279000e+02 +7 8160 -6.356400e+02 4.714000e+02 +14 8160 7.633002e+01 2.835500e+02 +16 8160 -1.877100e+02 4.231700e+02 +19 8160 9.981599e+02 3.526400e+02 +7 8161 -6.035600e+02 4.772700e+02 +14 8161 9.315002e+01 2.877900e+02 +19 8161 1.032330e+03 3.665300e+02 +7 8162 3.320699e+02 4.847700e+02 +13 8162 -1.536830e+03 1.089190e+03 +7 8163 4.239100e+02 4.877300e+02 +12 8163 -5.414300e+02 -4.700200e+02 +7 8164 -6.448100e+02 5.233700e+02 +19 8164 9.876799e+02 4.132600e+02 +7 8165 -6.448100e+02 5.233700e+02 +16 8165 -1.945600e+02 4.603201e+02 +19 8165 9.876799e+02 4.132600e+02 +7 8166 -9.308200e+02 5.246500e+02 +14 8166 -1.008400e+02 3.530600e+02 +19 8166 4.477800e+02 4.732100e+02 +7 8167 -5.692900e+02 5.319399e+02 +16 8167 -1.469000e+02 4.692300e+02 +18 8167 -1.234830e+03 2.117100e+02 +19 8167 1.069130e+03 4.388600e+02 +7 8168 1.164540e+03 5.447100e+02 +18 8168 1.853900e+02 1.705601e+02 +20 8168 1.626500e+02 -4.803003e+01 +7 8169 -1.267260e+03 5.629800e+02 +10 8169 -1.658060e+03 -1.451700e+02 +7 8170 -1.354970e+03 5.631799e+02 +19 8170 -4.088000e+01 4.849500e+02 +7 8171 -3.639000e+02 5.678101e+02 +16 8171 -1.022998e+01 5.017400e+02 +19 8171 1.320320e+03 5.233201e+02 +7 8172 -7.613500e+02 5.676700e+02 +16 8172 -3.437700e+02 4.903600e+02 +7 8173 -7.743900e+02 6.742100e+02 +10 8173 -1.173370e+03 -6.028003e+01 +16 8173 -3.558600e+02 5.674600e+02 +7 8174 -8.239400e+02 6.922500e+02 +10 8174 -1.214550e+03 -4.246997e+01 +14 8174 -3.344000e+01 4.457300e+02 +16 8174 -3.982600e+02 5.766799e+02 +19 8174 5.984301e+02 6.908700e+02 +7 8175 -7.373300e+02 7.113201e+02 +16 8175 -3.164000e+02 5.927900e+02 +7 8176 -9.101800e+02 7.122100e+02 +15 8176 7.468700e+02 4.464100e+02 +16 8176 -4.652000e+02 5.894100e+02 +7 8177 -9.898100e+02 7.866700e+02 +10 8177 -1.359680e+03 5.476001e+01 +15 8177 6.824200e+02 4.966600e+02 +16 8177 -5.272700e+02 6.405300e+02 +20 8177 -1.248910e+03 1.413600e+02 +7 8178 -1.143930e+03 8.086100e+02 +16 8178 -6.373100e+02 6.491500e+02 +20 8178 -1.362600e+03 1.601100e+02 +7 8179 -1.155370e+03 8.580500e+02 +10 8179 -1.513690e+03 1.265900e+02 +20 8179 -1.369010e+03 1.964000e+02 +7 8180 -1.151540e+03 1.017540e+03 +19 8180 1.913800e+02 1.040760e+03 +7 8181 -1.087110e+03 1.446100e+02 +16 8181 -5.857900e+02 1.762600e+02 +7 8182 5.189001e+01 1.481200e+02 +16 8182 3.306995e+01 1.889000e+02 +7 8183 -1.136550e+03 2.005400e+02 +15 8183 3.986700e+02 5.976001e+01 +16 8183 -7.766700e+02 2.100300e+02 +7 8184 -1.136550e+03 2.005400e+02 +15 8184 3.986700e+02 5.976001e+01 +16 8184 -7.766700e+02 2.100300e+02 +7 8185 5.984900e+02 2.430400e+02 +16 8185 5.091200e+02 2.759600e+02 +20 8185 1.942004e+01 -3.050000e+02 +7 8186 4.176001e+01 2.545300e+02 +16 8186 2.658199e+02 2.775300e+02 +7 8187 4.717000e+02 2.730901e+02 +16 8187 4.068300e+02 2.977400e+02 +7 8188 1.211450e+03 2.881200e+02 +12 8188 5.355005e+01 -5.573000e+02 +7 8189 -4.813000e+01 2.907500e+02 +14 8189 4.288800e+02 2.009200e+02 +7 8190 1.015700e+03 2.924700e+02 +17 8190 -9.797100e+02 3.407400e+02 +7 8191 -7.812100e+02 3.076300e+02 +15 8191 8.535800e+02 1.407500e+02 +7 8192 -7.812100e+02 3.076300e+02 +10 8192 -1.199980e+03 -4.038500e+02 +14 8192 -1.673999e+01 2.209900e+02 +15 8192 8.535800e+02 1.407500e+02 +7 8193 -7.427600e+02 3.159000e+02 +10 8193 -1.209970e+03 -3.929600e+02 +15 8193 8.893500e+02 1.478100e+02 +16 8193 -3.251900e+02 3.072000e+02 +7 8194 -8.004004e+01 3.257200e+02 +16 8194 1.605699e+02 3.297800e+02 +7 8195 5.228000e+02 3.291500e+02 +16 8195 4.472500e+02 3.442100e+02 +7 8196 5.228000e+02 3.291500e+02 +16 8196 4.472500e+02 3.442100e+02 +7 8197 5.772000e+02 3.417800e+02 +16 8197 4.910800e+02 3.565500e+02 +18 8197 -8.089966e+00 -5.902002e+01 +7 8198 -7.393500e+02 3.425601e+02 +14 8198 8.859985e+00 2.380800e+02 +15 8198 8.922300e+02 1.691900e+02 +16 8198 -3.226900e+02 3.266300e+02 +19 8198 7.243601e+02 2.408800e+02 +7 8199 9.015400e+02 3.470701e+02 +17 8199 -9.691800e+02 4.777400e+02 +7 8200 4.926500e+02 3.495100e+02 +16 8200 4.224600e+02 3.588400e+02 +7 8201 4.725200e+02 3.527000e+02 +13 8201 4.093999e+02 6.724200e+02 +16 8201 4.069700e+02 3.628101e+02 +7 8202 4.725200e+02 3.527000e+02 +13 8202 4.107200e+02 6.733400e+02 +16 8202 4.069700e+02 3.628101e+02 +7 8203 2.375400e+02 3.557300e+02 +12 8203 -8.717600e+02 -4.839900e+02 +7 8204 -9.952800e+02 3.565100e+02 +14 8204 -1.435300e+02 2.572700e+02 +7 8205 -8.323900e+02 3.662900e+02 +10 8205 -1.242010e+03 -3.484200e+02 +15 8205 8.073400e+02 1.863200e+02 +7 8206 -1.015960e+03 3.757400e+02 +15 8206 6.594399e+02 1.895700e+02 +16 8206 -5.387300e+02 3.432800e+02 +7 8207 -7.487000e+02 4.349099e+02 +14 8207 5.850006e+00 2.919300e+02 +19 8207 7.124299e+02 3.597700e+02 +7 8208 -7.583600e+02 4.353101e+02 +16 8208 -3.398500e+02 3.937400e+02 +19 8208 6.981299e+02 3.606500e+02 +7 8209 1.276440e+03 4.376000e+02 +12 8209 1.023700e+02 -4.079200e+02 +7 8210 -1.099390e+03 4.635801e+02 +14 8210 -2.008100e+02 3.211800e+02 +7 8211 -6.930100e+02 4.742700e+02 +10 8211 -1.125090e+03 -2.501801e+02 +7 8212 -3.464900e+02 4.816000e+02 +14 8212 2.370600e+02 2.983100e+02 +19 8212 1.337530e+03 4.160300e+02 +7 8213 -3.464900e+02 4.816000e+02 +14 8213 2.372700e+02 2.984600e+02 +18 8213 -9.996900e+02 1.550901e+02 +19 8213 1.337530e+03 4.160300e+02 +7 8214 -6.362200e+02 5.013900e+02 +14 8214 7.728003e+01 2.990600e+02 +16 8214 -1.895000e+02 4.448800e+02 +7 8215 1.185080e+03 5.050500e+02 +12 8215 1.806995e+01 -3.380200e+02 +7 8216 -6.029100e+02 5.073401e+02 +14 8216 9.532001e+01 3.030900e+02 +16 8216 -1.675000e+02 4.506500e+02 +19 8216 1.033620e+03 4.013401e+02 +7 8217 -2.471997e+01 5.098101e+02 +12 8217 -1.138620e+03 -3.219800e+02 +7 8218 1.082260e+03 5.125200e+02 +12 8218 -7.589001e+01 -3.303900e+02 +20 8218 1.151000e+02 -6.638000e+01 +7 8219 -6.520300e+02 5.146300e+02 +14 8219 6.906000e+01 3.053600e+02 +16 8219 -1.997400e+02 4.538101e+02 +7 8220 -7.416700e+02 5.184199e+02 +16 8220 -3.254800e+02 4.544100e+02 +7 8221 4.448600e+02 5.221000e+02 +17 8221 -1.834900e+02 9.744600e+02 +7 8222 -6.204800e+02 5.218500e+02 +14 8222 8.553003e+01 3.103100e+02 +7 8223 -8.927300e+02 5.230500e+02 +14 8223 -7.857999e+01 3.512000e+02 +7 8224 -5.866900e+02 5.284000e+02 +10 8224 -1.064100e+03 -2.020900e+02 +14 8224 1.033800e+02 3.152300e+02 +16 8224 -1.588700e+02 4.656200e+02 +19 8224 1.049870e+03 4.308700e+02 +20 8224 -1.077680e+03 -1.842999e+01 +7 8225 -9.649700e+02 5.297900e+02 +10 8225 -1.355840e+03 -1.891000e+02 +14 8225 -1.210800e+02 3.573400e+02 +16 8225 -5.046300e+02 4.553000e+02 +19 8225 4.003000e+02 4.786599e+02 +7 8226 -6.519200e+02 5.339299e+02 +16 8226 -1.988700e+02 4.679600e+02 +19 8226 9.809500e+02 4.249700e+02 +7 8227 -6.882996e+01 5.377600e+02 +16 8227 1.865699e+02 4.888201e+02 +7 8228 -6.882996e+01 5.377600e+02 +16 8228 1.865699e+02 4.888201e+02 +7 8229 -5.261600e+02 5.379000e+02 +14 8229 1.369800e+02 3.230800e+02 +18 8229 -1.186190e+03 2.146200e+02 +7 8230 -1.116250e+03 5.392700e+02 +14 8230 -2.078800e+02 3.650800e+02 +19 8230 2.142800e+02 4.809299e+02 +7 8231 -6.210100e+02 5.401899e+02 +16 8231 -1.792800e+02 4.739100e+02 +19 8231 1.014360e+03 4.378101e+02 +7 8232 -5.785600e+02 5.449900e+02 +19 8232 1.059720e+03 4.503401e+02 +7 8233 -5.875400e+02 5.468800e+02 +10 8233 -1.065040e+03 -1.850699e+02 +14 8233 1.036700e+02 3.234300e+02 +16 8233 -1.581800e+02 4.791400e+02 +19 8233 1.050490e+03 4.518900e+02 +7 8234 -4.846200e+02 5.497600e+02 +16 8234 -9.265002e+01 4.845500e+02 +19 8234 1.166070e+03 4.773201e+02 +7 8235 -4.934400e+02 5.533700e+02 +19 8235 1.154900e+03 4.810100e+02 +7 8236 -5.790600e+02 5.601400e+02 +16 8236 -1.532100e+02 4.887300e+02 +19 8236 1.059550e+03 4.675300e+02 +7 8237 -5.592200e+02 5.656700e+02 +10 8237 -1.032310e+03 -1.692100e+02 +7 8238 -1.133080e+03 5.823400e+02 +16 8238 -6.266900e+02 4.873000e+02 +19 8238 1.960300e+02 5.298900e+02 +7 8239 -4.465700e+02 6.056600e+02 +19 8239 1.219940e+03 5.527900e+02 +7 8240 -1.211899e+02 6.196799e+02 +16 8240 1.537700e+02 5.494000e+02 +7 8241 5.145900e+02 6.361600e+02 +18 8241 -5.506006e+01 1.396000e+02 +7 8242 -3.661400e+02 6.393400e+02 +16 8242 -4.669983e+00 5.552600e+02 +19 8242 1.331500e+03 6.048600e+02 +7 8243 -8.681400e+02 6.729399e+02 +10 8243 -1.254450e+03 -5.614001e+01 +19 8243 5.311400e+02 6.649900e+02 +7 8244 -8.799800e+02 6.755701e+02 +19 8244 5.155300e+02 6.676899e+02 +7 8245 -9.535600e+02 6.850300e+02 +10 8245 -1.331930e+03 -4.176001e+01 +7 8246 -9.646000e+02 6.869100e+02 +10 8246 -1.342570e+03 -3.960999e+01 +7 8247 -8.454100e+02 7.090300e+02 +15 8247 8.010800e+02 4.475400e+02 +16 8247 -4.163000e+02 5.899399e+02 +7 8248 -1.176880e+03 7.278201e+02 +10 8248 -1.548640e+03 8.369995e+00 +19 8248 1.491100e+02 6.994100e+02 +7 8249 -8.628800e+02 7.339100e+02 +10 8249 -1.244530e+03 -6.199951e-01 +11 8249 -9.825300e+02 6.315200e+02 +14 8249 -5.629999e+01 4.732400e+02 +15 8249 7.850300e+02 4.662100e+02 +19 8249 5.384900e+02 7.406799e+02 +20 8249 -1.162940e+03 1.019099e+02 +7 8250 -7.672400e+02 7.405200e+02 +10 8250 -1.163790e+03 1.390015e+00 +7 8251 -9.997100e+02 7.543900e+02 +15 8251 6.755200e+02 4.717600e+02 +7 8252 -7.651300e+02 7.930900e+02 +14 8252 4.059998e+00 4.960100e+02 +7 8253 -1.244520e+03 7.946600e+02 +10 8253 -1.609900e+03 7.314001e+01 +16 8253 -7.067500e+02 6.349600e+02 +7 8254 -1.221940e+03 8.078700e+02 +10 8254 -1.586110e+03 8.456006e+01 +15 8254 5.169700e+02 4.946799e+02 +16 8254 -6.904800e+02 6.451700e+02 +19 8254 1.032000e+02 7.868300e+02 +7 8255 -9.844400e+02 8.117000e+02 +16 8255 -5.234000e+02 6.586100e+02 +7 8256 -1.298250e+03 8.689299e+02 +10 8256 -1.658660e+03 1.447700e+02 +16 8256 -7.439400e+02 6.857700e+02 +7 8257 -1.248670e+03 1.056110e+03 +10 8257 -1.593320e+03 3.097100e+02 +7 8258 1.651899e+02 6.915002e+01 +16 8258 1.327900e+02 1.269700e+02 +7 8259 -8.704400e+02 1.835300e+02 +16 8259 -4.270000e+02 2.084900e+02 +7 8260 -1.099610e+03 1.944000e+02 +19 8260 2.246899e+02 5.769995e+01 +7 8261 -7.562700e+02 2.003600e+02 +16 8261 -3.582600e+02 2.217200e+02 +7 8262 -1.128420e+03 2.043401e+02 +15 8262 4.049200e+02 6.270001e+01 +16 8262 -7.708700e+02 2.128500e+02 +7 8263 -8.099200e+02 2.049600e+02 +10 8263 -1.229940e+03 -5.060000e+02 +14 8263 -3.700000e+01 1.621700e+02 +7 8264 -8.739000e+02 2.051000e+02 +15 8264 7.680800e+02 6.097998e+01 +7 8265 -1.417100e+02 2.272700e+02 +14 8265 3.676900e+02 1.619800e+02 +7 8266 1.004430e+03 2.278101e+02 +12 8266 -1.329301e+02 -6.125800e+02 +17 8266 -8.747800e+02 1.954500e+02 +20 8266 9.543005e+01 -2.591899e+02 +7 8267 5.028000e+02 2.418800e+02 +13 8267 5.425100e+02 2.106500e+02 +7 8268 4.474399e+02 2.414900e+02 +12 8268 -5.247800e+02 -6.792300e+02 +16 8268 3.879000e+02 2.715300e+02 +18 8268 -9.573999e+01 -1.257600e+02 +20 8268 -6.892004e+01 -3.058300e+02 +7 8269 -1.087480e+03 2.519500e+02 +19 8269 2.417800e+02 1.291100e+02 +7 8270 2.135100e+02 2.538301e+02 +16 8270 3.361500e+02 2.787500e+02 +7 8271 5.476001e+01 2.615601e+02 +16 8271 2.792000e+02 2.831500e+02 +7 8272 -3.162000e+01 2.651899e+02 +14 8272 4.390400e+02 1.846000e+02 +7 8273 4.737200e+02 2.662500e+02 +13 8273 4.196899e+02 3.178500e+02 +16 8273 4.087000e+02 2.925300e+02 +18 8273 -7.802002e+01 -1.091801e+02 +7 8274 9.513899e+02 2.678401e+02 +17 8274 -8.432500e+02 2.923800e+02 +18 8274 6.546997e+01 -4.522998e+01 +7 8275 6.077200e+02 2.874000e+02 +16 8275 5.155800e+02 3.120100e+02 +7 8276 1.002510e+03 2.920100e+02 +12 8276 -1.328300e+02 -5.533300e+02 +17 8276 -7.283300e+02 3.453201e+02 +7 8277 -1.607100e+02 2.951599e+02 +16 8277 1.056000e+02 3.038700e+02 +7 8278 -9.969971e+00 2.970500e+02 +16 8278 2.152900e+02 3.091100e+02 +7 8279 6.108900e+02 3.060601e+02 +16 8279 5.183400e+02 3.269700e+02 +7 8280 9.966399e+02 3.111699e+02 +17 8280 -7.398400e+02 3.891899e+02 +7 8281 -7.352400e+02 3.218401e+02 +15 8281 8.965300e+02 1.523500e+02 +16 8281 -3.200000e+02 3.119600e+02 +19 8281 7.352000e+02 2.118401e+02 +7 8282 -2.162000e+01 3.232800e+02 +14 8282 4.463000e+02 2.203400e+02 +7 8283 3.838000e+01 3.256500e+02 +16 8283 2.664399e+02 3.315701e+02 +7 8284 3.838000e+01 3.256500e+02 +16 8284 2.664399e+02 3.315701e+02 +7 8285 1.001310e+03 3.300100e+02 +12 8285 -1.339399e+02 -5.182500e+02 +20 8285 9.371997e+01 -1.946400e+02 +7 8286 6.003600e+02 3.350601e+02 +16 8286 5.101300e+02 3.510900e+02 +7 8287 1.078170e+03 3.433600e+02 +12 8287 -6.530005e+01 -5.041400e+02 +7 8288 4.992600e+02 3.547000e+02 +16 8288 4.282800e+02 3.647200e+02 +7 8289 8.689500e+02 3.565200e+02 +12 8289 -2.584600e+02 -4.887000e+02 +7 8290 5.271200e+02 3.749600e+02 +16 8290 4.502600e+02 3.823800e+02 +7 8291 -1.033740e+03 3.753800e+02 +15 8291 6.446899e+02 1.891200e+02 +7 8292 -1.033740e+03 3.753800e+02 +16 8292 -5.505900e+02 3.426400e+02 +7 8293 6.016100e+02 3.762300e+02 +16 8293 5.108300e+02 3.854900e+02 +7 8294 -1.129080e+03 3.774700e+02 +16 8294 -6.203000e+02 3.420400e+02 +19 8294 1.969700e+02 2.825601e+02 +7 8295 -5.769800e+02 3.838600e+02 +14 8295 1.057100e+02 2.386400e+02 +7 8296 -4.841000e+02 3.942000e+02 +14 8296 1.564900e+02 2.461400e+02 +18 8296 -1.144390e+03 8.814001e+01 +7 8297 -4.449700e+02 3.999199e+02 +16 8297 -6.503998e+01 3.768400e+02 +19 8297 1.213190e+03 2.938301e+02 +7 8298 -5.090300e+02 4.017200e+02 +14 8298 1.428400e+02 2.500000e+02 +7 8299 -8.215900e+02 4.183500e+02 +14 8299 -4.034000e+01 2.877600e+02 +7 8300 -1.117160e+03 4.259099e+02 +14 8300 -2.119200e+02 2.992700e+02 +16 8300 -6.125900e+02 3.767800e+02 +7 8301 -3.318600e+02 4.309800e+02 +16 8301 9.459961e+00 4.019000e+02 +18 8301 -9.859400e+02 1.098000e+02 +19 8301 1.357240e+03 3.509500e+02 +7 8302 -7.424100e+02 4.329399e+02 +14 8302 9.799988e+00 2.906500e+02 +16 8302 -3.245500e+02 3.919399e+02 +7 8303 -5.712200e+02 4.336599e+02 +14 8303 1.096700e+02 2.647100e+02 +19 8303 1.066970e+03 3.158900e+02 +7 8304 -2.844500e+02 4.369199e+02 +14 8304 2.727500e+02 2.747300e+02 +7 8305 -2.844500e+02 4.369199e+02 +16 8305 4.107996e+01 4.073000e+02 +7 8306 -5.197100e+02 4.407200e+02 +14 8306 1.380200e+02 2.705300e+02 +16 8306 -1.142300e+02 4.034299e+02 +19 8306 1.125380e+03 3.319500e+02 +20 8306 -1.016860e+03 -8.756995e+01 +7 8307 1.040300e+02 4.444700e+02 +16 8307 3.147700e+02 4.225500e+02 +7 8308 1.040300e+02 4.444700e+02 +16 8308 3.147700e+02 4.225500e+02 +7 8309 -4.561500e+02 4.506100e+02 +20 8309 -9.587000e+02 -8.353003e+01 +7 8310 -4.561500e+02 4.506100e+02 +20 8310 -9.587400e+02 -8.275000e+01 +7 8311 4.869995e+00 4.688900e+02 +16 8311 2.397200e+02 4.394500e+02 +7 8312 4.448900e+02 4.796300e+02 +16 8312 3.806400e+02 4.665100e+02 +7 8313 -6.447400e+02 4.826699e+02 +14 8313 7.208002e+01 2.889000e+02 +16 8313 -1.945800e+02 4.312600e+02 +19 8313 9.875200e+02 3.636599e+02 +7 8314 -6.931700e+02 4.849700e+02 +10 8314 -1.124620e+03 -2.386899e+02 +16 8314 -2.765500e+02 4.308600e+02 +7 8315 1.107780e+03 4.890500e+02 +17 8315 -7.818800e+02 7.926600e+02 +18 8315 1.482900e+02 1.320801e+02 +20 8315 1.310900e+02 -8.079004e+01 +7 8316 -2.698101e+02 4.921100e+02 +20 8316 -7.903200e+02 -6.260999e+01 +7 8317 -4.307600e+02 4.951899e+02 +16 8317 -5.710999e+01 4.469200e+02 +7 8318 -6.932100e+02 4.990300e+02 +10 8318 -1.124280e+03 -2.255500e+02 +7 8319 2.713300e+02 5.103700e+02 +12 8319 -8.361600e+02 -3.271600e+02 +7 8320 1.601700e+02 5.145200e+02 +18 8320 -5.345800e+02 1.546699e+02 +7 8321 -7.947000e+02 5.142900e+02 +16 8321 -3.740400e+02 4.503500e+02 +7 8322 1.167160e+03 5.151200e+02 +17 8322 -6.558400e+02 8.425701e+02 +7 8323 -4.048600e+02 5.160901e+02 +16 8323 -4.053003e+01 4.626799e+02 +19 8323 1.262300e+03 4.513600e+02 +7 8324 -6.119200e+02 5.232200e+02 +19 8324 1.023870e+03 4.190300e+02 +7 8325 -5.863500e+02 5.372300e+02 +10 8325 -1.063820e+03 -1.939800e+02 +7 8326 -5.195400e+02 5.476300e+02 +14 8326 1.399100e+02 3.279000e+02 +19 8326 1.125010e+03 4.683500e+02 +7 8327 -5.593600e+02 5.508700e+02 +14 8327 1.181600e+02 3.274000e+02 +7 8328 -6.000100e+02 5.544299e+02 +10 8328 -1.076840e+03 -1.775900e+02 +7 8329 -5.657200e+02 5.605000e+02 +10 8329 -1.040330e+03 -1.733900e+02 +16 8329 -1.454700e+02 4.899900e+02 +19 8329 1.072570e+03 4.748700e+02 +20 8329 -1.056690e+03 4.309998e+00 +7 8330 -2.705500e+02 5.611600e+02 +20 8330 -8.090800e+02 -8.270020e+00 +7 8331 -4.672400e+02 5.658201e+02 +14 8331 1.689600e+02 3.397900e+02 +7 8332 -2.915400e+02 5.660300e+02 +18 8332 -9.661200e+02 2.284800e+02 +7 8333 -1.095890e+03 5.678400e+02 +14 8333 -1.952100e+02 3.814400e+02 +16 8333 -5.988900e+02 4.784000e+02 +19 8333 2.390699e+02 5.166599e+02 +7 8334 -8.078300e+02 5.751100e+02 +10 8334 -1.207370e+03 -1.505300e+02 +19 8334 6.200400e+02 5.404500e+02 +7 8335 -8.078300e+02 5.751100e+02 +19 8335 6.200400e+02 5.404500e+02 +7 8336 -1.191830e+03 5.820500e+02 +15 8336 5.355300e+02 3.352200e+02 +7 8337 -4.029600e+02 5.869399e+02 +16 8337 -3.309998e+01 5.152200e+02 +7 8338 -4.912800e+02 5.875300e+02 +16 8338 -9.696997e+01 5.126200e+02 +19 8338 1.159270e+03 5.225901e+02 +7 8339 -2.654004e+01 5.887800e+02 +12 8339 -1.152520e+03 -2.364800e+02 +18 8339 -7.083100e+02 2.243600e+02 +7 8340 -4.708997e+01 5.921200e+02 +12 8340 -1.175360e+03 -2.287400e+02 +7 8341 4.855800e+02 5.960900e+02 +12 8341 -4.906600e+02 -3.762600e+02 +7 8342 -1.008730e+03 6.055900e+02 +20 8342 -1.270140e+03 1.003998e+01 +7 8343 -9.730400e+02 6.093600e+02 +10 8343 -1.357110e+03 -1.119800e+02 +7 8344 -3.168000e+02 6.209800e+02 +14 8344 2.530600e+02 3.666000e+02 +7 8345 -3.528300e+02 6.297200e+02 +16 8345 7.760010e+00 5.484500e+02 +7 8346 -1.235150e+03 6.350500e+02 +19 8346 8.616003e+01 5.822300e+02 +7 8347 -1.367520e+03 6.355701e+02 +16 8347 -7.856700e+02 5.173201e+02 +7 8348 -4.616600e+02 6.421700e+02 +16 8348 -7.459998e+01 5.541100e+02 +19 8348 1.200600e+03 5.955000e+02 +20 8348 -9.640300e+02 6.018994e+01 +7 8349 -3.767600e+02 6.444100e+02 +19 8349 1.316620e+03 6.101500e+02 +7 8350 -1.298690e+03 6.553101e+02 +19 8350 1.865002e+01 5.981300e+02 +7 8351 -7.656500e+02 6.581500e+02 +16 8351 -3.475500e+02 5.575400e+02 +7 8352 -6.992900e+02 6.723000e+02 +14 8352 4.140997e+01 4.181600e+02 +16 8352 -2.839000e+02 5.679500e+02 +7 8353 -6.992900e+02 6.723000e+02 +14 8353 4.140997e+01 4.181600e+02 +16 8353 -2.839000e+02 5.679500e+02 +19 8353 8.131899e+02 6.472300e+02 +7 8354 -9.120900e+02 7.037400e+02 +10 8354 -1.292880e+03 -2.656006e+01 +16 8354 -4.668000e+02 5.836400e+02 +7 8355 -1.370090e+03 7.055300e+02 +19 8355 -5.381995e+01 6.450200e+02 +7 8356 -7.899900e+02 7.302600e+02 +10 8356 -1.181030e+03 -7.099976e+00 +7 8357 -8.446700e+02 7.296200e+02 +10 8357 -1.228330e+03 -5.260010e+00 +14 8357 -4.481000e+01 4.696700e+02 +15 8357 7.999600e+02 4.639800e+02 +16 8357 -4.155500e+02 6.049500e+02 +19 8357 5.655800e+02 7.361700e+02 +7 8358 -8.521700e+02 7.310701e+02 +10 8358 -1.234850e+03 -3.680054e+00 +14 8358 -4.951999e+01 4.709100e+02 +15 8358 7.935500e+02 4.648101e+02 +19 8358 5.538000e+02 7.378600e+02 +7 8359 -1.001660e+03 7.359299e+02 +19 8359 3.548101e+02 7.304100e+02 +7 8360 -7.555900e+02 7.384200e+02 +10 8360 -1.153680e+03 -1.160034e+00 +7 8361 -9.020600e+02 7.401500e+02 +10 8361 -1.279700e+03 6.949951e+00 +15 8361 7.523101e+02 4.678700e+02 +19 8361 4.852000e+02 7.459500e+02 +7 8362 -9.121000e+02 7.419900e+02 +10 8362 -1.288830e+03 9.199951e+00 +14 8362 -8.454999e+01 4.793201e+02 +15 8362 7.437300e+02 4.688800e+02 +7 8363 -9.439500e+02 7.468201e+02 +10 8363 -1.317990e+03 1.497998e+01 +15 8363 7.192300e+02 4.700300e+02 +19 8363 4.287700e+02 7.509000e+02 +7 8364 -9.534400e+02 7.475900e+02 +10 8364 -1.327000e+03 1.630005e+01 +14 8364 -1.092800e+02 4.840100e+02 +15 8364 7.115699e+02 4.697900e+02 +20 8364 -1.223420e+03 1.116500e+02 +7 8365 -1.041580e+03 7.512000e+02 +19 8365 3.064900e+02 7.452600e+02 +7 8366 -1.014940e+03 7.553600e+02 +10 8366 -1.383430e+03 2.570996e+01 +7 8367 -1.138390e+03 7.583101e+02 +15 8367 5.738400e+02 4.652700e+02 +19 8367 1.920200e+02 7.413300e+02 +7 8368 -1.172220e+03 7.592600e+02 +16 8368 -6.556200e+02 6.128101e+02 +7 8369 -1.204240e+03 7.601500e+02 +16 8369 -6.781600e+02 6.120400e+02 +7 8370 -1.252410e+03 7.610900e+02 +16 8370 -7.106800e+02 6.109299e+02 +7 8371 -8.894300e+02 7.790300e+02 +14 8371 -7.054999e+01 4.995000e+02 +7 8372 -8.066500e+02 8.120601e+02 +16 8372 -3.849100e+02 6.663000e+02 +19 8372 6.249199e+02 8.392300e+02 +7 8373 -1.146890e+03 8.581799e+02 +10 8373 -1.506030e+03 1.272400e+02 +14 8373 -2.161100e+02 5.485500e+02 +15 8373 5.700500e+02 5.351700e+02 +20 8373 -1.363010e+03 1.967900e+02 +7 8374 -9.959200e+02 8.636799e+02 +15 8374 6.803199e+02 5.532200e+02 +16 8374 -5.312200e+02 6.965100e+02 +19 8374 3.683600e+02 8.829200e+02 +7 8375 -1.111730e+03 8.637800e+02 +10 8375 -1.469740e+03 1.303400e+02 +14 8375 -1.975100e+02 5.513101e+02 +15 8375 5.961400e+02 5.418600e+02 +16 8375 -6.157200e+02 6.907100e+02 +20 8375 -1.336020e+03 1.992600e+02 +7 8376 -1.279040e+03 8.899200e+02 +16 8376 -7.315700e+02 7.016700e+02 +7 8377 -9.410400e+02 9.131799e+02 +16 8377 -4.655300e+02 7.348700e+02 +7 8378 -1.089410e+03 9.215000e+02 +10 8378 -1.454220e+03 1.806699e+02 +14 8378 -1.781200e+02 5.746400e+02 +15 8378 6.220300e+02 5.865601e+02 +16 8378 -5.900300e+02 7.320400e+02 +19 8378 2.826801e+02 9.250500e+02 +20 8378 -1.335610e+03 2.476599e+02 +7 8379 -1.260990e+03 1.039920e+03 +10 8379 -1.606410e+03 2.990200e+02 +19 8379 7.731995e+01 1.041610e+03 +7 8380 -7.942000e+02 1.838700e+02 +16 8380 -3.658900e+02 2.103900e+02 +7 8381 -8.097600e+02 1.895000e+02 +15 8381 8.240800e+02 4.789001e+01 +7 8382 1.040550e+03 1.933101e+02 +17 8382 -6.326300e+02 1.174200e+02 +18 8382 1.308500e+02 -1.019500e+02 +7 8383 1.181400e+03 2.032900e+02 +12 8383 2.856006e+01 -6.362100e+02 +18 8383 2.283700e+02 -9.446997e+01 +20 8383 2.028300e+02 -2.747600e+02 +7 8384 -7.725500e+02 2.041599e+02 +16 8384 -3.705300e+02 2.248200e+02 +7 8385 -1.024300e+03 2.060701e+02 +16 8385 -6.275000e+02 2.189100e+02 +7 8386 -7.898200e+02 2.211200e+02 +14 8386 -2.478000e+01 1.711000e+02 +7 8387 -9.061500e+02 2.217300e+02 +15 8387 7.408800e+02 7.413000e+01 +7 8388 -8.888100e+02 2.388600e+02 +14 8388 -8.373999e+01 1.846500e+02 +16 8388 -4.429600e+02 2.473700e+02 +7 8389 6.827600e+02 2.403101e+02 +16 8389 8.906000e+02 2.773900e+02 +7 8390 -7.783200e+02 2.414099e+02 +10 8390 -1.199430e+03 -4.701400e+02 +14 8390 -1.707999e+01 1.820400e+02 +7 8391 -1.052200e+03 2.407300e+02 +14 8391 -1.791700e+02 1.904800e+02 +7 8392 -8.019400e+02 2.419500e+02 +10 8392 -1.221350e+03 -4.697100e+02 +14 8392 -3.125000e+01 1.835500e+02 +15 8392 8.313700e+02 8.938000e+01 +16 8392 -3.739600e+02 2.520200e+02 +7 8393 -9.808500e+02 2.458000e+02 +14 8393 -1.379200e+02 1.919000e+02 +15 8393 6.820100e+02 9.262000e+01 +16 8393 -5.120600e+02 2.509200e+02 +20 8393 -1.263180e+03 -2.562400e+02 +7 8394 -8.021800e+02 2.475200e+02 +10 8394 -1.221350e+03 -4.633700e+02 +11 8394 -9.123200e+02 1.229999e+01 +14 8394 -3.151001e+01 1.867800e+02 +15 8394 8.318900e+02 9.395001e+01 +16 8394 -3.746200e+02 2.562100e+02 +7 8395 -8.834300e+02 2.543101e+02 +14 8395 -7.998999e+01 1.940500e+02 +7 8396 3.108101e+02 2.581000e+02 +12 8396 -3.865601e+02 -8.157000e+02 +7 8397 -1.103630e+03 2.677000e+02 +15 8397 5.906300e+02 1.087300e+02 +16 8397 -6.006100e+02 2.639800e+02 +19 8397 2.223900e+02 1.482600e+02 +7 8398 -1.115650e+03 2.677100e+02 +14 8398 -2.144300e+02 2.071700e+02 +7 8399 -9.836600e+02 2.749700e+02 +16 8399 -5.144200e+02 2.718800e+02 +7 8400 -1.102350e+03 2.768401e+02 +19 8400 2.243101e+02 1.598201e+02 +7 8401 4.750200e+02 2.797900e+02 +16 8401 4.090900e+02 3.030300e+02 +7 8402 4.750200e+02 2.797900e+02 +16 8402 4.090900e+02 3.030300e+02 +7 8403 -8.838000e+02 2.798301e+02 +14 8403 -7.979999e+01 2.083000e+02 +7 8404 4.840200e+02 2.943600e+02 +16 8404 4.167900e+02 3.154000e+02 +7 8405 -1.103250e+03 2.946000e+02 +19 8405 2.238600e+02 1.816500e+02 +7 8406 5.271100e+02 2.999800e+02 +13 8406 6.405901e+02 4.510300e+02 +16 8406 4.484200e+02 3.224000e+02 +7 8407 5.283000e+02 3.056300e+02 +16 8407 4.534700e+02 3.249900e+02 +7 8408 5.286100e+02 3.117400e+02 +16 8408 4.526600e+02 3.306500e+02 +7 8409 -8.247800e+02 3.127800e+02 +20 8409 -1.155900e+03 -2.034399e+02 +7 8410 -1.116240e+03 3.128900e+02 +19 8410 2.092100e+02 1.927000e+02 +7 8411 -1.104540e+03 3.305601e+02 +14 8411 -2.070000e+02 2.435600e+02 +15 8411 5.914399e+02 1.546500e+02 +19 8411 2.226000e+02 2.258600e+02 +7 8412 -8.298800e+02 3.450601e+02 +10 8412 -1.240920e+03 -3.683500e+02 +15 8412 8.086200e+02 1.696900e+02 +16 8412 -3.981100e+02 3.260500e+02 +18 8412 -1.343320e+03 2.472998e+01 +20 8412 -1.157010e+03 -1.798199e+02 +7 8413 3.619399e+02 3.461799e+02 +12 8413 -7.603600e+02 -4.868700e+02 +18 8413 -4.006801e+02 2.672998e+01 +7 8414 2.757400e+02 3.464299e+02 +12 8414 -8.380400e+02 -4.914900e+02 +13 8414 -1.666860e+03 5.403500e+02 +7 8415 -8.860000e+02 3.510801e+02 +15 8415 7.602900e+02 1.732200e+02 +7 8416 1.317210e+03 3.521000e+02 +12 8416 1.407600e+02 -4.900000e+02 +7 8417 1.317210e+03 3.521000e+02 +12 8417 1.407600e+02 -4.900000e+02 +7 8418 -7.416000e+02 3.562800e+02 +10 8418 -1.163280e+03 -3.593700e+02 +14 8418 8.089996e+00 2.465500e+02 +16 8418 -3.231100e+02 3.360701e+02 +7 8419 1.106260e+03 3.589800e+02 +12 8419 -4.153003e+01 -4.898700e+02 +7 8420 3.615500e+02 3.591200e+02 +12 8420 -7.602600e+02 -4.729200e+02 +7 8421 -8.869700e+02 3.587100e+02 +14 8421 -7.982999e+01 2.550300e+02 +16 8421 -4.429000e+02 3.340200e+02 +7 8422 -8.563300e+02 3.611100e+02 +14 8422 -4.217999e+01 2.528300e+02 +7 8423 -9.288200e+02 3.606400e+02 +15 8423 7.259900e+02 1.796300e+02 +7 8424 -8.623000e+02 3.679600e+02 +10 8424 -1.269070e+03 -3.457600e+02 +14 8424 -6.417999e+01 2.596600e+02 +15 8424 7.812200e+02 1.869100e+02 +16 8424 -4.230700e+02 3.418600e+02 +7 8425 -9.902500e+02 3.678800e+02 +19 8425 3.645699e+02 2.758600e+02 +7 8426 -1.030940e+03 3.687600e+02 +15 8426 6.468700e+02 1.842500e+02 +7 8427 -1.030940e+03 3.687600e+02 +14 8427 -1.633900e+02 2.645600e+02 +15 8427 6.468700e+02 1.842500e+02 +19 8427 3.140800e+02 2.754299e+02 +7 8428 -9.204100e+02 3.701300e+02 +15 8428 7.324500e+02 1.871100e+02 +7 8429 -1.126920e+03 3.708301e+02 +19 8429 1.984700e+02 2.743201e+02 +7 8430 -9.955800e+02 3.725000e+02 +16 8430 -5.250200e+02 3.415900e+02 +7 8431 -5.869400e+02 3.834500e+02 +14 8431 1.001800e+02 2.378600e+02 +16 8431 -1.570400e+02 3.598800e+02 +19 8431 1.049730e+03 2.511799e+02 +7 8432 1.155280e+03 3.862900e+02 +20 8432 1.840601e+02 -1.595800e+02 +7 8433 1.155280e+03 3.862900e+02 +18 8433 2.079700e+02 3.984998e+01 +20 8433 1.840601e+02 -1.595800e+02 +7 8434 -6.241500e+02 3.891799e+02 +10 8434 -1.111050e+03 -3.317700e+02 +16 8434 -1.800600e+02 3.637600e+02 +19 8434 1.009680e+03 2.535500e+02 +7 8435 1.129010e+03 3.907900e+02 +20 8435 1.691300e+02 -1.558400e+02 +7 8436 -6.022600e+02 3.921200e+02 +16 8436 -1.662700e+02 3.664900e+02 +19 8436 1.033590e+03 2.600400e+02 +7 8437 -3.801400e+02 3.943600e+02 +19 8437 1.295410e+03 2.965200e+02 +7 8438 -1.109410e+03 3.957200e+02 +16 8438 -6.067600e+02 3.553300e+02 +19 8438 2.188400e+02 3.060701e+02 +7 8439 -1.116220e+03 3.958401e+02 +19 8439 2.110400e+02 3.055400e+02 +7 8440 1.109300e+03 3.987100e+02 +18 8440 1.751500e+02 5.083997e+01 +7 8441 -5.375800e+02 4.007100e+02 +10 8441 -1.018610e+03 -3.223900e+02 +14 8441 1.273800e+02 2.483700e+02 +16 8441 -1.251500e+02 3.741300e+02 +19 8441 1.105550e+03 2.795200e+02 +7 8442 2.110300e+02 4.053401e+02 +18 8442 -4.963600e+02 6.805005e+01 +7 8443 -2.676400e+02 4.086300e+02 +16 8443 5.287000e+01 3.875200e+02 +7 8444 1.223760e+03 4.100300e+02 +18 8444 2.557000e+02 5.688000e+01 +7 8445 -7.580500e+02 4.106400e+02 +10 8445 -1.175380e+03 -3.072800e+02 +14 8445 -1.600037e-01 2.785400e+02 +15 8445 9.069600e+02 2.165300e+02 +16 8445 -3.125500e+02 3.706700e+02 +19 8445 7.499500e+02 3.133301e+02 +7 8446 -7.949500e+02 4.136100e+02 +10 8446 -1.205090e+03 -3.033800e+02 +7 8447 -8.133500e+02 4.186799e+02 +10 8447 -1.222830e+03 -2.982000e+02 +11 8447 -9.271900e+02 2.302100e+02 +16 8447 -3.866900e+02 3.796200e+02 +18 8447 -1.331660e+03 8.784009e+01 +7 8448 1.290790e+03 4.273600e+02 +18 8448 2.885200e+02 7.657007e+01 +7 8449 -5.217300e+02 4.316200e+02 +19 8449 1.123060e+03 3.209700e+02 +7 8450 -8.593900e+02 4.328500e+02 +15 8450 7.852200e+02 2.364900e+02 +7 8451 -5.079100e+02 4.335801e+02 +14 8451 1.440700e+02 2.672100e+02 +7 8452 5.431600e+02 4.424399e+02 +10 8452 1.374050e+03 -2.251801e+02 +7 8453 1.153770e+03 4.437700e+02 +18 8453 2.046899e+02 8.446997e+01 +7 8454 -1.129960e+03 4.464099e+02 +14 8454 -2.174200e+02 3.111700e+02 +19 8454 1.953600e+02 3.660400e+02 +7 8455 -8.368000e+02 4.508900e+02 +10 8455 -1.240250e+03 -2.661300e+02 +11 8455 -9.490400e+02 2.707900e+02 +15 8455 8.044900e+02 2.511000e+02 +7 8456 -5.602600e+02 4.523101e+02 +10 8456 -1.039610e+03 -2.739200e+02 +14 8456 1.348100e+02 2.793700e+02 +16 8456 -1.406500e+02 4.116000e+02 +19 8456 1.079110e+03 3.410300e+02 +20 8456 -1.054170e+03 -7.714001e+01 +7 8457 -9.320200e+02 4.539600e+02 +14 8457 -1.034900e+02 3.121600e+02 +15 8457 7.252300e+02 2.506100e+02 +7 8458 -5.018200e+02 4.611100e+02 +14 8458 1.481500e+02 2.821000e+02 +16 8458 -1.029900e+02 4.197400e+02 +19 8458 1.146110e+03 3.619099e+02 +7 8459 -9.188600e+02 4.627900e+02 +15 8459 7.364301e+02 2.575400e+02 +19 8459 4.618199e+02 3.966100e+02 +7 8460 -9.364900e+02 4.647500e+02 +15 8460 7.220000e+02 2.586400e+02 +7 8461 -4.845700e+02 4.684099e+02 +19 8461 1.165990e+03 3.742800e+02 +7 8462 -6.498400e+02 4.738000e+02 +14 8462 6.945001e+01 2.840900e+02 +7 8463 4.649301e+02 4.772600e+02 +12 8463 -5.063500e+02 -4.780500e+02 +16 8463 3.968900e+02 4.644500e+02 +7 8464 -7.760600e+02 4.782300e+02 +19 8464 6.702600e+02 4.159700e+02 +7 8465 -6.184100e+02 4.790801e+02 +16 8465 -1.776800e+02 4.304900e+02 +7 8466 -6.127200e+02 4.816699e+02 +16 8466 -1.737600e+02 4.310800e+02 +7 8467 -6.127200e+02 4.816699e+02 +16 8467 -1.737600e+02 4.310800e+02 +19 8467 1.022690e+03 3.698201e+02 +7 8468 4.384700e+02 4.835000e+02 +16 8468 3.754100e+02 4.691400e+02 +7 8469 4.403500e+02 4.962600e+02 +17 8469 -1.895100e+02 9.072900e+02 +7 8470 -7.415400e+02 5.017800e+02 +14 8470 1.192999e+01 3.301500e+02 +15 8470 8.926600e+02 2.948600e+02 +16 8470 -3.276100e+02 4.434000e+02 +19 8470 7.224099e+02 4.464199e+02 +7 8471 -2.692800e+02 5.045901e+02 +14 8471 2.834900e+02 3.133000e+02 +18 8471 -9.223200e+02 1.682900e+02 +7 8472 2.265200e+02 5.072000e+02 +20 8472 -4.110000e+02 -6.933997e+01 +7 8473 1.094060e+03 5.088800e+02 +20 8473 1.230699e+02 -6.820996e+01 +7 8474 -3.808800e+02 5.093500e+02 +14 8474 2.175100e+02 3.127700e+02 +19 8474 1.293250e+03 4.473301e+02 +7 8475 -5.845400e+02 5.201799e+02 +14 8475 1.046700e+02 3.113300e+02 +16 8475 -1.566100e+02 4.605200e+02 +20 8475 -1.075040e+03 -2.414001e+01 +7 8476 -5.845400e+02 5.201799e+02 +14 8476 1.046700e+02 3.113300e+02 +16 8476 -1.566100e+02 4.605200e+02 +20 8476 -1.075040e+03 -2.414001e+01 +7 8477 -6.240002e+01 5.228000e+02 +14 8477 4.144000e+02 3.324400e+02 +7 8478 -1.873300e+02 5.278401e+02 +12 8478 -1.326070e+03 -2.889900e+02 +7 8479 -1.178470e+03 5.315601e+02 +19 8479 1.456700e+02 4.647600e+02 +7 8480 -6.305005e+01 5.346899e+02 +16 8480 1.915000e+02 4.874500e+02 +7 8481 -6.338300e+02 5.389600e+02 +16 8481 -1.878000e+02 4.732800e+02 +7 8482 -6.282800e+02 5.416899e+02 +14 8482 8.207001e+01 3.200400e+02 +16 8482 -1.844200e+02 4.743201e+02 +7 8483 -8.883200e+02 5.424000e+02 +10 8483 -1.282600e+03 -1.777400e+02 +11 8483 -1.005340e+03 3.847800e+02 +7 8484 -6.013900e+02 5.454299e+02 +10 8484 -1.079180e+03 -1.862100e+02 +7 8485 -1.895699e+02 5.483800e+02 +14 8485 3.332600e+02 3.426000e+02 +18 8485 -8.414200e+02 1.983201e+02 +7 8486 -1.835400e+02 5.497400e+02 +14 8486 3.374900e+02 3.440000e+02 +7 8487 1.131995e+01 5.540000e+02 +16 8487 2.451700e+02 5.050601e+02 +20 8487 -5.581800e+02 -3.357996e+01 +7 8488 -1.323510e+03 5.562100e+02 +15 8488 4.460200e+02 3.116300e+02 +16 8488 -7.552300e+02 4.624900e+02 +19 8488 -1.090002e+01 4.803700e+02 +7 8489 -9.294100e+02 5.562100e+02 +10 8489 -1.320000e+03 -1.641000e+02 +14 8489 -9.976999e+01 3.717300e+02 +15 8489 7.283000e+02 3.278600e+02 +16 8489 -4.779500e+02 4.757100e+02 +19 8489 4.487500e+02 5.126500e+02 +7 8490 -1.281920e+03 5.570000e+02 +14 8490 -2.983700e+02 3.745800e+02 +19 8490 3.420996e+01 4.859199e+02 +7 8491 -7.534700e+02 5.610601e+02 +19 8491 7.068101e+02 5.198401e+02 +7 8492 1.215900e+02 5.636200e+02 +16 8492 3.276801e+02 5.151799e+02 +7 8493 -2.649000e+02 5.653000e+02 +16 8493 6.575000e+01 5.040400e+02 +7 8494 -1.019000e+02 5.668700e+02 +18 8494 -7.666200e+02 2.110300e+02 +7 8495 -5.228000e+02 5.757600e+02 +16 8495 -1.190000e+02 5.011700e+02 +19 8495 1.119810e+03 5.018401e+02 +7 8496 -1.121590e+03 5.799299e+02 +10 8496 -1.504580e+03 -1.343101e+02 +7 8497 -8.018400e+02 5.805900e+02 +14 8497 -2.301999e+01 3.804200e+02 +7 8498 -8.223100e+02 5.974700e+02 +14 8498 -3.476999e+01 3.912200e+02 +19 8498 5.987100e+02 5.691000e+02 +7 8499 -1.111550e+03 5.966799e+02 +14 8499 -2.041000e+02 3.982600e+02 +19 8499 2.193000e+02 5.505701e+02 +7 8500 -8.897500e+02 5.994399e+02 +14 8500 -7.514001e+01 3.952400e+02 +19 8500 5.023101e+02 5.699800e+02 +7 8501 6.401399e+02 6.037400e+02 +16 8501 5.539399e+02 5.721000e+02 +7 8502 -9.753600e+02 6.037000e+02 +16 8502 -5.135200e+02 5.087100e+02 +19 8502 3.878800e+02 5.706300e+02 +7 8503 -1.310770e+03 6.085400e+02 +16 8503 -7.469000e+02 5.001500e+02 +7 8504 -8.962500e+02 6.136100e+02 +14 8504 -7.875000e+01 4.045100e+02 +15 8504 7.564399e+02 3.730200e+02 +16 8504 -4.533000e+02 5.185100e+02 +7 8505 5.819301e+02 6.152700e+02 +12 8505 -4.091200e+02 -3.633600e+02 +7 8506 -9.300300e+02 6.165800e+02 +14 8506 -9.825000e+01 4.067000e+02 +19 8506 4.484500e+02 5.889000e+02 +7 8507 -3.110300e+02 6.202400e+02 +14 8507 2.564100e+02 3.661700e+02 +7 8508 -5.380600e+02 6.250701e+02 +16 8508 -1.247700e+02 5.377900e+02 +19 8508 1.110130e+03 5.546699e+02 +7 8509 -8.670000e+02 6.330701e+02 +14 8509 -6.076001e+01 4.147000e+02 +15 8509 7.801899e+02 3.890900e+02 +19 8509 5.327100e+02 6.137200e+02 +7 8510 -8.811800e+02 6.347200e+02 +14 8510 -6.900000e+01 4.163201e+02 +7 8511 -8.811800e+02 6.347200e+02 +14 8511 -6.900000e+01 4.163201e+02 +19 8511 5.122800e+02 6.153700e+02 +7 8512 -1.327660e+03 6.369399e+02 +19 8512 -9.420044e+00 5.726000e+02 +7 8513 -4.291000e+02 6.398800e+02 +16 8513 -5.215997e+01 5.527200e+02 +7 8514 -1.256590e+03 6.542100e+02 +19 8514 6.287000e+01 6.020000e+02 +7 8515 -7.013800e+02 6.785500e+02 +14 8515 4.091998e+01 4.214500e+02 +16 8515 -2.855600e+02 5.723201e+02 +7 8516 -1.343850e+03 6.877200e+02 +14 8516 -3.296700e+02 4.494399e+02 +15 8516 4.340300e+02 4.026100e+02 +19 8516 -3.222998e+01 6.323201e+02 +7 8517 -1.409380e+03 6.891799e+02 +19 8517 -9.859998e+01 6.255300e+02 +7 8518 -8.083700e+02 7.039399e+02 +19 8518 6.200100e+02 7.037500e+02 +7 8519 -1.279930e+03 7.047500e+02 +10 8519 -1.655590e+03 -8.829956e+00 +7 8520 -7.260500e+02 7.093201e+02 +16 8520 -3.060700e+02 5.932700e+02 +7 8521 -8.174900e+02 7.156400e+02 +15 8521 8.240500e+02 4.554399e+02 +19 8521 6.057900e+02 7.190400e+02 +7 8522 -8.400000e+02 7.210900e+02 +14 8522 -4.260001e+01 4.639800e+02 +15 8522 8.044700e+02 4.580200e+02 +19 8522 5.732400e+02 7.249000e+02 +7 8523 -8.479000e+02 7.230200e+02 +10 8523 -1.233020e+03 -1.143994e+01 +14 8523 -4.745001e+01 4.653900e+02 +15 8523 7.976300e+02 4.588000e+02 +19 8523 5.616600e+02 7.268800e+02 +7 8524 -8.561800e+02 7.248600e+02 +14 8524 -5.214999e+01 4.669399e+02 +15 8524 7.906400e+02 4.596400e+02 +19 8524 5.498300e+02 7.288800e+02 +7 8525 -1.147040e+03 7.250701e+02 +10 8525 -1.517860e+03 4.290039e+00 +7 8526 -9.057000e+02 7.339700e+02 +14 8526 -8.135001e+01 4.742500e+02 +19 8526 4.814600e+02 7.370300e+02 +7 8527 -8.456500e+02 7.401100e+02 +19 8527 5.655500e+02 7.495000e+02 +7 8528 -8.569200e+02 7.421899e+02 +10 8528 -1.238630e+03 7.410034e+00 +14 8528 -5.172000e+01 4.775900e+02 +16 8528 -4.251300e+02 6.134800e+02 +7 8529 -1.211940e+03 7.515800e+02 +16 8529 -6.831300e+02 6.053600e+02 +7 8530 -9.488700e+02 7.570701e+02 +10 8530 -1.322260e+03 2.489001e+01 +15 8530 7.144600e+02 4.771600e+02 +7 8531 -1.157820e+03 7.593000e+02 +19 8531 1.707400e+02 7.391700e+02 +7 8532 -1.383520e+03 7.587700e+02 +14 8532 -3.480800e+02 4.875200e+02 +15 8532 4.116100e+02 4.494500e+02 +19 8532 -6.462000e+01 7.059800e+02 +7 8533 -8.064100e+02 7.600601e+02 +14 8533 -2.166000e+01 4.841400e+02 +7 8534 -8.894800e+02 7.633101e+02 +14 8534 -7.104001e+01 4.903101e+02 +15 8534 7.623900e+02 4.898600e+02 +7 8535 -1.352990e+03 7.630500e+02 +19 8535 -3.347998e+01 7.150000e+02 +7 8536 -1.378550e+03 7.635300e+02 +19 8536 -5.940002e+01 7.119000e+02 +7 8537 -1.014170e+03 7.652900e+02 +16 8537 -5.446400e+02 6.235000e+02 +7 8538 -9.684800e+02 7.700500e+02 +20 8538 -1.234620e+03 1.290300e+02 +7 8539 -8.179900e+02 8.028000e+02 +16 8539 -3.931600e+02 6.593900e+02 +7 8540 -1.127590e+03 8.148600e+02 +10 8540 -1.488160e+03 8.685999e+01 +15 8540 5.822000e+02 5.066400e+02 +16 8540 -6.276300e+02 6.533700e+02 +19 8540 2.039900e+02 8.098101e+02 +20 8540 -1.347980e+03 1.639800e+02 +7 8541 -1.290100e+03 8.170800e+02 +16 8541 -7.373800e+02 6.487500e+02 +7 8542 -1.058960e+03 8.343500e+02 +15 8542 6.346899e+02 5.259900e+02 +19 8542 2.943000e+02 8.393600e+02 +7 8543 -1.058960e+03 8.343500e+02 +15 8543 6.346899e+02 5.259900e+02 +19 8543 2.943000e+02 8.393600e+02 +7 8544 -8.855500e+02 8.385800e+02 +19 8544 5.112900e+02 8.669299e+02 +7 8545 -9.776400e+02 8.395100e+02 +16 8545 -5.179700e+02 6.787500e+02 +7 8546 -9.839100e+02 8.402300e+02 +16 8546 -5.226400e+02 6.789301e+02 +7 8547 -9.492200e+02 8.431600e+02 +19 8547 4.315800e+02 8.640200e+02 +7 8548 -9.987500e+02 8.532500e+02 +15 8548 6.785900e+02 5.453400e+02 +7 8549 -1.117960e+03 8.624299e+02 +10 8549 -1.475930e+03 1.292200e+02 +7 8550 -1.127510e+03 8.722600e+02 +14 8550 -2.056600e+02 5.551700e+02 +16 8550 -6.259100e+02 6.952000e+02 +20 8550 -1.349760e+03 2.066200e+02 +7 8551 -1.272870e+03 8.791500e+02 +16 8551 -7.273300e+02 6.940100e+02 +7 8552 -1.163260e+03 8.999000e+02 +16 8552 -6.516200e+02 7.133101e+02 +7 8553 -1.358330e+03 9.251100e+02 +15 8553 4.403800e+02 5.657100e+02 +7 8554 -1.117060e+03 9.823000e+02 +14 8554 -1.888700e+02 6.033800e+02 +7 8555 -1.435200e+02 1.964600e+02 +16 8555 1.124301e+02 2.291700e+02 +7 8556 1.063500e+03 1.983600e+02 +12 8556 -7.648999e+01 -6.420200e+02 +18 8556 1.472100e+02 -9.873999e+01 +7 8557 6.706599e+02 1.993000e+02 +16 8557 5.642800e+02 2.403300e+02 +7 8558 -1.069260e+03 1.998000e+02 +19 8558 2.639000e+02 6.394995e+01 +7 8559 1.149730e+03 2.044900e+02 +12 8559 -6.994629e-02 -6.355601e+02 +7 8560 4.981600e+02 2.165300e+02 +13 8560 5.242600e+02 1.081700e+02 +7 8561 -9.843800e+02 2.266400e+02 +15 8561 6.780300e+02 7.806000e+01 +16 8561 -5.144300e+02 2.369000e+02 +20 8561 -1.266790e+03 -2.704100e+02 +7 8562 -9.900800e+02 2.265801e+02 +16 8562 -5.187600e+02 2.369000e+02 +7 8563 4.057800e+02 2.400000e+02 +12 8563 -7.243600e+02 -5.898400e+02 +18 8563 -3.777600e+02 -5.402002e+01 +7 8564 -7.903400e+02 2.424800e+02 +10 8564 -1.209940e+03 -4.689900e+02 +15 8564 8.413101e+02 8.976001e+01 +7 8565 -8.360000e+02 2.470100e+02 +10 8565 -1.252810e+03 -4.634399e+02 +7 8566 -9.072600e+02 2.473500e+02 +15 8566 7.405800e+02 9.358002e+01 +16 8566 -4.580500e+02 2.538600e+02 +7 8567 -8.886600e+02 2.513401e+02 +15 8567 7.572100e+02 9.673999e+01 +7 8568 -1.002490e+03 2.553700e+02 +15 8568 6.666500e+02 9.983002e+01 +7 8569 1.006340e+03 2.750300e+02 +12 8569 -1.286400e+02 -5.689700e+02 +7 8570 -8.718700e+02 2.789800e+02 +19 8570 5.217300e+02 1.631400e+02 +7 8571 -7.873700e+02 3.037700e+02 +16 8571 -3.630200e+02 2.972200e+02 +19 8571 6.477400e+02 1.927700e+02 +7 8572 1.107380e+03 3.054299e+02 +20 8572 1.567300e+02 -2.098000e+02 +7 8573 1.107380e+03 3.054299e+02 +20 8573 1.567300e+02 -2.098000e+02 +7 8574 -7.675000e+02 3.086699e+02 +10 8574 -1.188300e+03 -4.044800e+02 +14 8574 -8.880005e+00 2.195900e+02 +15 8574 8.656801e+02 1.409600e+02 +19 8574 6.810100e+02 1.966699e+02 +7 8575 -8.015800e+02 3.119800e+02 +10 8575 -1.217460e+03 -4.012000e+02 +7 8576 -9.802400e+02 3.143101e+02 +14 8576 -1.356500e+02 2.318200e+02 +7 8577 -8.767000e+02 3.170300e+02 +14 8577 -7.451999e+01 2.302300e+02 +16 8577 -4.346400e+02 3.044700e+02 +19 8577 5.157800e+02 2.122200e+02 +7 8578 -7.555000e+02 3.173301e+02 +19 8578 7.009600e+02 2.085400e+02 +7 8579 1.336670e+03 3.180500e+02 +12 8579 1.589200e+02 -5.211300e+02 +18 8579 3.244301e+02 -5.030029e+00 +7 8580 -8.112500e+02 3.223101e+02 +14 8580 -3.441000e+01 2.306400e+02 +16 8580 -3.821000e+02 3.103201e+02 +19 8580 6.135601e+02 2.179000e+02 +7 8581 -9.351900e+02 3.232300e+02 +19 8581 4.379399e+02 2.201400e+02 +7 8582 -8.589800e+02 3.248600e+02 +19 8582 5.402900e+02 2.222000e+02 +7 8583 -1.051870e+03 3.264299e+02 +14 8583 -1.760400e+02 2.401900e+02 +19 8583 2.881899e+02 2.217700e+02 +7 8584 -7.917900e+02 3.340200e+02 +16 8584 -3.700900e+02 3.192700e+02 +7 8585 -7.504500e+02 3.365400e+02 +15 8585 8.826200e+02 1.639600e+02 +7 8586 -7.901000e+02 3.405200e+02 +10 8586 -1.203390e+03 -3.737900e+02 +15 8586 8.424800e+02 1.664000e+02 +19 8586 6.402700e+02 2.419700e+02 +7 8587 -9.203100e+02 3.406699e+02 +19 8587 4.557700e+02 2.427700e+02 +7 8588 -8.750100e+02 3.460000e+02 +10 8588 -1.281420e+03 -3.668700e+02 +16 8588 -4.345900e+02 3.256000e+02 +19 8588 5.165300e+02 2.503900e+02 +7 8589 -1.125920e+03 3.455901e+02 +14 8589 -2.187300e+02 2.528500e+02 +7 8590 -1.125920e+03 3.455901e+02 +14 8590 -2.187300e+02 2.528500e+02 +15 8590 5.752200e+02 1.659100e+02 +7 8591 1.326590e+03 3.470500e+02 +12 8591 1.494100e+02 -4.949100e+02 +7 8592 -8.816400e+02 3.467600e+02 +14 8592 -7.698999e+01 2.483100e+02 +15 8592 7.635800e+02 1.699900e+02 +19 8592 5.069000e+02 2.503201e+02 +7 8593 -8.912600e+02 3.470100e+02 +10 8593 -1.298250e+03 -3.653400e+02 +15 8593 7.564100e+02 1.698900e+02 +7 8594 -9.939800e+02 3.500400e+02 +14 8594 -1.430500e+02 2.533400e+02 +15 8594 6.723400e+02 1.712700e+02 +19 8594 3.583101e+02 2.536899e+02 +7 8595 -1.050380e+03 3.518401e+02 +15 8595 7.230200e+02 1.707300e+02 +7 8596 -7.609600e+02 3.522300e+02 +10 8596 -1.179450e+03 -3.628800e+02 +14 8596 -3.410004e+00 2.453000e+02 +15 8596 8.721500e+02 1.764300e+02 +16 8596 -3.415600e+02 3.335300e+02 +19 8596 6.898601e+02 2.543201e+02 +7 8597 -8.099500e+02 3.533101e+02 +19 8597 6.146300e+02 2.573900e+02 +7 8598 -1.126310e+03 3.533000e+02 +14 8598 -2.179600e+02 2.571700e+02 +7 8599 -1.004360e+03 3.549099e+02 +15 8599 6.658600e+02 1.745900e+02 +19 8599 3.479100e+02 2.589000e+02 +7 8600 4.905000e+02 3.568401e+02 +13 8600 4.862700e+02 6.862100e+02 +7 8601 -1.122370e+03 3.572800e+02 +16 8601 -6.148800e+02 3.275601e+02 +7 8602 5.675200e+02 3.596699e+02 +13 8602 8.026201e+02 6.894900e+02 +7 8603 -8.317400e+02 3.598201e+02 +15 8603 8.074900e+02 1.808800e+02 +16 8603 -3.990400e+02 3.369000e+02 +7 8604 -8.634200e+02 3.625400e+02 +10 8604 -1.270140e+03 -3.507700e+02 +7 8605 -8.634200e+02 3.625400e+02 +10 8605 -1.270140e+03 -3.507700e+02 +7 8606 -1.121330e+03 3.672200e+02 +16 8606 -5.177700e+02 3.354399e+02 +7 8607 -9.678100e+02 3.676000e+02 +15 8607 6.949500e+02 1.842800e+02 +7 8608 -9.853200e+02 3.718301e+02 +14 8608 -1.373200e+02 2.658800e+02 +15 8608 6.808199e+02 1.874600e+02 +7 8609 -9.157700e+02 3.730000e+02 +16 8609 -4.643300e+02 3.443400e+02 +7 8610 1.109350e+03 3.912500e+02 +12 8610 -3.970996e+01 -4.595699e+02 +13 8610 1.596030e+03 6.330100e+02 +7 8611 1.109350e+03 3.912500e+02 +12 8611 -3.970996e+01 -4.595699e+02 +13 8611 1.596030e+03 6.330100e+02 +7 8612 -7.427800e+02 3.921799e+02 +10 8612 -1.162670e+03 -3.253300e+02 +7 8613 -7.427800e+02 3.921799e+02 +10 8613 -1.162670e+03 -3.253300e+02 +15 8613 8.912100e+02 2.084300e+02 +16 8613 -3.257800e+02 3.635100e+02 +7 8614 -8.038800e+02 3.991899e+02 +10 8614 -1.214200e+03 -3.168300e+02 +11 8614 -9.161500e+02 2.059900e+02 +14 8614 -2.866000e+01 2.747300e+02 +16 8614 -3.778400e+02 3.654600e+02 +7 8615 1.157240e+03 4.044900e+02 +18 8615 2.102000e+02 5.451001e+01 +7 8616 -7.843300e+02 4.098000e+02 +15 8616 8.508700e+02 2.207200e+02 +16 8616 -3.614500e+02 3.745601e+02 +19 8616 6.546599e+02 3.290801e+02 +7 8617 -8.040200e+02 4.118301e+02 +10 8617 -1.213630e+03 -3.048000e+02 +15 8617 8.328101e+02 2.219000e+02 +16 8617 -3.780900e+02 3.752200e+02 +19 8617 6.243301e+02 3.320901e+02 +7 8618 1.072580e+03 4.150801e+02 +20 8618 1.366801e+02 -1.414700e+02 +7 8619 -6.207600e+02 4.167000e+02 +16 8619 -1.788800e+02 3.840601e+02 +19 8619 1.013290e+03 2.876500e+02 +7 8620 -1.101060e+03 4.207400e+02 +14 8620 -2.028100e+02 2.963300e+02 +7 8621 -1.101060e+03 4.207400e+02 +15 8621 5.954399e+02 2.214500e+02 +19 8621 2.288400e+02 3.370000e+02 +7 8622 9.398799e+02 4.233800e+02 +17 8622 -8.742200e+02 6.579399e+02 +7 8623 9.570801e+02 4.241899e+02 +17 8623 -8.334100e+02 6.578300e+02 +7 8624 1.072510e+03 4.377700e+02 +13 8624 1.485660e+03 8.157200e+02 +17 8624 -5.745800e+02 6.759600e+02 +7 8625 1.171780e+03 4.414700e+02 +12 8625 1.376001e+01 -4.131899e+02 +18 8625 2.085601e+02 8.222998e+01 +20 8625 1.918500e+02 -1.236400e+02 +7 8626 8.429700e+02 4.415300e+02 +12 8626 -2.968700e+02 -3.906300e+02 +7 8627 -6.232000e+02 4.453800e+02 +14 8627 8.342999e+01 2.700800e+02 +16 8627 -1.793300e+02 4.048500e+02 +7 8628 -8.783600e+02 4.495000e+02 +10 8628 -1.278340e+03 -2.667800e+02 +15 8628 7.681000e+02 2.487100e+02 +16 8628 -4.385900e+02 4.006500e+02 +7 8629 -6.937200e+02 4.542500e+02 +16 8629 -2.761700e+02 4.092200e+02 +7 8630 -8.045700e+02 4.553101e+02 +10 8630 -1.211610e+03 -2.629700e+02 +11 8630 -9.183800e+02 2.775600e+02 +15 8630 8.327700e+02 2.558600e+02 +18 8630 -1.323810e+03 1.193500e+02 +19 8630 6.239100e+02 3.887600e+02 +7 8631 -9.869000e+02 4.567100e+02 +15 8631 6.824200e+02 2.511100e+02 +7 8632 -6.408400e+02 4.672900e+02 +16 8632 -1.908000e+02 4.209900e+02 +7 8633 4.440400e+02 4.690000e+02 +16 8633 3.823700e+02 4.573700e+02 +7 8634 -3.102900e+02 4.753500e+02 +14 8634 2.584000e+02 2.958700e+02 +19 8634 1.384900e+03 4.151000e+02 +7 8635 -1.139060e+03 4.764900e+02 +19 8635 1.873300e+02 4.021899e+02 +7 8636 1.102940e+03 4.977100e+02 +12 8636 -5.548999e+01 -3.433300e+02 +17 8636 -7.919600e+02 8.114600e+02 +18 8636 1.449700e+02 1.386899e+02 +20 8636 1.285000e+02 -7.514001e+01 +7 8637 -3.872800e+02 5.004700e+02 +19 8637 1.284480e+03 4.345901e+02 +7 8638 -6.121200e+02 5.049500e+02 +19 8638 1.022970e+03 3.943201e+02 +7 8639 -6.121200e+02 5.049500e+02 +19 8639 1.023390e+03 3.982700e+02 +7 8640 -6.384300e+02 5.081699e+02 +16 8640 -1.895200e+02 4.504000e+02 +7 8641 -8.251000e+02 5.079000e+02 +20 8641 -1.149300e+03 -6.007996e+01 +7 8642 1.165240e+03 5.095200e+02 +17 8642 -6.593101e+02 8.297600e+02 +20 8642 1.673400e+02 -6.914001e+01 +7 8643 -6.189300e+02 5.117200e+02 +14 8643 8.626001e+01 3.050900e+02 +16 8643 -1.781500e+02 4.532000e+02 +7 8644 -6.189300e+02 5.117200e+02 +14 8644 8.626001e+01 3.050900e+02 +16 8644 -1.781500e+02 4.532000e+02 +7 8645 -7.719100e+02 5.236100e+02 +10 8645 -1.179760e+03 -1.993199e+02 +19 8645 6.772700e+02 4.737900e+02 +7 8646 -7.447900e+02 5.269199e+02 +14 8646 1.020999e+01 3.449400e+02 +7 8647 -7.447900e+02 5.269199e+02 +10 8647 -1.156530e+03 -1.989200e+02 +7 8648 -6.878100e+02 5.298401e+02 +10 8648 -1.118470e+03 -1.967400e+02 +14 8648 4.482001e+01 3.378600e+02 +16 8648 -2.729400e+02 4.653400e+02 +7 8649 -6.878100e+02 5.298401e+02 +10 8649 -1.118470e+03 -1.967400e+02 +14 8649 4.482001e+01 3.378600e+02 +16 8649 -2.729400e+02 4.653400e+02 +7 8650 -3.867900e+02 5.358600e+02 +14 8650 2.145800e+02 3.264600e+02 +16 8650 -2.647998e+01 4.782800e+02 +18 8650 -1.042970e+03 2.032900e+02 +7 8651 1.161960e+03 5.363401e+02 +12 8651 -2.849976e+00 -3.090601e+02 +18 8651 1.868900e+02 1.653500e+02 +7 8652 -3.208400e+02 5.406300e+02 +16 8652 2.205005e+01 4.834600e+02 +7 8653 -8.064600e+02 5.411699e+02 +10 8653 -1.207860e+03 -1.829100e+02 +19 8653 6.220500e+02 4.979399e+02 +7 8654 -7.642400e+02 5.437500e+02 +16 8654 -3.457900e+02 4.734299e+02 +7 8655 -1.109700e+02 5.439299e+02 +16 8655 1.572500e+02 4.930000e+02 +7 8656 -7.012000e+01 5.448500e+02 +16 8656 1.861801e+02 4.950701e+02 +18 8656 -7.274100e+02 1.874600e+02 +7 8657 -3.218900e+02 5.451200e+02 +18 8657 -9.871100e+02 2.088700e+02 +7 8658 -3.455400e+02 5.532000e+02 +14 8658 2.376900e+02 3.353400e+02 +7 8659 -1.050420e+03 5.542500e+02 +15 8659 6.348500e+02 3.213500e+02 +19 8659 2.930200e+02 5.038201e+02 +7 8660 -9.231700e+02 5.550701e+02 +15 8660 7.339301e+02 3.271200e+02 +7 8661 -9.690700e+02 5.614600e+02 +15 8661 6.972600e+02 3.302300e+02 +19 8661 3.958700e+02 5.178000e+02 +7 8662 -9.381000e+02 5.705800e+02 +15 8662 7.221400e+02 3.389700e+02 +7 8663 -1.136810e+03 5.715701e+02 +14 8663 -2.180200e+02 3.834299e+02 +7 8664 -1.672000e+02 5.778300e+02 +18 8664 -8.237600e+02 2.226500e+02 +7 8665 -1.180940e+03 5.796200e+02 +16 8665 -6.591500e+02 4.843000e+02 +19 8665 9.268994e+01 5.203900e+02 +7 8666 -3.201000e+02 5.798300e+02 +16 8666 2.543005e+01 5.121400e+02 +19 8666 1.388940e+03 5.399000e+02 +7 8667 -1.644600e+02 5.893400e+02 +12 8667 -1.298120e+03 -2.280200e+02 +18 8667 -8.216200e+02 2.313101e+02 +7 8668 4.948700e+02 6.034100e+02 +18 8668 -6.696997e+01 1.191000e+02 +20 8668 -4.525000e+01 -9.544995e+01 +7 8669 -8.369000e+02 6.042000e+02 +19 8669 5.778700e+02 5.769800e+02 +7 8670 4.851300e+02 6.092400e+02 +12 8670 -4.933400e+02 -3.647200e+02 +7 8671 -7.928200e+02 6.177200e+02 +14 8671 -1.684000e+01 4.019000e+02 +16 8671 -3.726100e+02 5.253900e+02 +19 8671 6.413999e+02 5.960601e+02 +7 8672 -5.118500e+02 6.231500e+02 +14 8672 1.458800e+02 3.675200e+02 +18 8672 -1.175640e+03 2.886300e+02 +20 8672 -1.009250e+03 4.909998e+01 +7 8673 -1.261480e+03 6.296600e+02 +15 8673 4.902600e+02 3.663201e+02 +7 8674 -1.201000e+03 6.314600e+02 +19 8674 1.214600e+02 5.817900e+02 +7 8675 -7.503400e+02 6.332800e+02 +10 8675 -1.152880e+03 -9.720996e+01 +7 8676 -3.565100e+02 6.358400e+02 +14 8676 2.317100e+02 3.756800e+02 +16 8676 3.630005e+00 5.528300e+02 +19 8676 1.346610e+03 6.001799e+02 +7 8677 -3.565100e+02 6.358400e+02 +16 8677 3.630005e+00 5.528300e+02 +7 8678 -1.351560e+03 6.391000e+02 +15 8678 4.297100e+02 3.683400e+02 +7 8679 -3.971500e+02 6.401600e+02 +16 8679 -2.671002e+01 5.545500e+02 +7 8680 -1.100030e+03 6.451200e+02 +10 8680 -1.477690e+03 -7.306995e+01 +19 8680 2.320699e+02 6.112600e+02 +7 8681 -1.144850e+03 6.519200e+02 +19 8681 1.832100e+02 6.135000e+02 +7 8682 -1.174020e+03 6.520200e+02 +14 8682 -2.370700e+02 4.298300e+02 +7 8683 -1.094100e+02 6.524000e+02 +16 8683 1.596100e+02 5.750601e+02 +7 8684 -1.065480e+03 6.562800e+02 +19 8684 2.745900e+02 6.275300e+02 +7 8685 -1.105510e+03 6.558300e+02 +10 8685 -1.481250e+03 -6.271997e+01 +16 8685 -6.090100e+02 5.411300e+02 +19 8685 2.260900e+02 6.235800e+02 +7 8686 -1.149060e+03 6.565200e+02 +19 8686 1.779000e+02 6.187400e+02 +7 8687 -1.173330e+03 6.964900e+02 +15 8687 5.489500e+02 4.184900e+02 +7 8688 -1.221900e+03 6.973800e+02 +10 8688 -1.598070e+03 -1.818005e+01 +16 8688 -6.882900e+02 5.665400e+02 +7 8689 -1.244160e+03 6.977900e+02 +15 8689 5.008600e+02 4.152900e+02 +7 8690 -1.362330e+03 7.003700e+02 +16 8690 -7.839100e+02 5.630701e+02 +7 8691 -7.779100e+02 7.035400e+02 +15 8691 8.600800e+02 4.487700e+02 +19 8691 6.663799e+02 7.038101e+02 +7 8692 -8.080000e+02 7.044399e+02 +14 8692 -2.394000e+01 4.521100e+02 +15 8692 8.321801e+02 4.472500e+02 +7 8693 -7.834900e+02 7.054900e+02 +14 8693 -9.019989e+00 4.510800e+02 +7 8694 -7.834900e+02 7.054900e+02 +10 8694 -1.177630e+03 -3.001001e+01 +7 8695 -8.871900e+02 7.259900e+02 +10 8695 -1.268380e+03 -6.949951e+00 +14 8695 -7.082999e+01 4.689200e+02 +16 8695 -4.488100e+02 6.004299e+02 +7 8696 -8.731700e+02 7.282000e+02 +10 8696 -1.254950e+03 -5.430054e+00 +19 8696 5.260400e+02 7.320900e+02 +7 8697 -8.880500e+02 7.353300e+02 +14 8697 -7.073001e+01 4.746400e+02 +15 8697 7.635699e+02 4.654500e+02 +7 8698 -1.218720e+03 7.377800e+02 +16 8698 -6.877400e+02 5.954500e+02 +19 8698 1.050900e+02 7.047900e+02 +7 8699 -9.965000e+02 7.410200e+02 +15 8699 6.772700e+02 4.624600e+02 +16 8699 -5.313000e+02 6.068700e+02 +19 8699 3.618400e+02 7.380400e+02 +7 8700 -9.919100e+02 7.459000e+02 +14 8700 -1.316300e+02 4.835601e+02 +7 8701 -7.274800e+02 7.576899e+02 +20 8701 -1.093410e+03 1.271300e+02 +7 8702 -9.287800e+02 7.646700e+02 +10 8702 -1.303870e+03 3.106995e+01 +7 8703 -9.495500e+02 7.665500e+02 +10 8703 -1.322700e+03 3.363000e+01 +7 8704 -9.969200e+02 7.718500e+02 +16 8704 -5.327100e+02 6.286899e+02 +19 8704 3.623800e+02 7.754000e+02 +7 8705 -9.969200e+02 7.718500e+02 +10 8705 -1.367120e+03 4.106006e+01 +7 8706 -1.169600e+03 7.748600e+02 +10 8706 -1.534020e+03 5.122998e+01 +19 8706 1.553300e+02 7.570100e+02 +7 8707 -1.056380e+03 7.801500e+02 +10 8707 -1.423440e+03 5.095996e+01 +15 8707 6.338199e+02 4.866600e+02 +20 8707 -1.296410e+03 1.375500e+02 +7 8708 -8.682100e+02 7.815200e+02 +15 8708 7.844600e+02 5.011400e+02 +19 8708 5.436200e+02 7.945500e+02 +7 8709 -9.933000e+02 7.908600e+02 +19 8709 3.668800e+02 7.986799e+02 +7 8710 -1.379490e+03 7.945900e+02 +15 8710 4.147400e+02 4.741500e+02 +7 8711 -1.152190e+03 8.034399e+02 +19 8711 1.777300e+02 7.925800e+02 +7 8712 -1.176620e+03 8.174399e+02 +10 8712 -1.581900e+03 9.368994e+01 +7 8713 -8.787800e+02 8.213500e+02 +16 8713 -4.433500e+02 6.699399e+02 +7 8714 -9.917100e+02 8.413500e+02 +14 8714 -1.296600e+02 5.386200e+02 +15 8714 6.815900e+02 5.366700e+02 +19 8714 3.687800e+02 8.603800e+02 +7 8715 -1.364180e+03 8.417600e+02 +15 8715 4.275500e+02 5.068201e+02 +7 8716 -1.250670e+03 8.688900e+02 +16 8716 -6.590200e+02 6.892600e+02 +7 8717 -1.223400e+03 8.839100e+02 +16 8717 -6.941900e+02 6.995200e+02 +7 8718 -9.946000e+02 8.914600e+02 +15 8718 6.802600e+02 5.738101e+02 +7 8719 -1.025380e+03 8.970800e+02 +16 8719 -5.449300e+02 7.167600e+02 +19 8719 3.528400e+02 9.070200e+02 +20 8719 -1.283150e+03 2.265200e+02 +7 8720 -1.205630e+03 9.283800e+02 +15 8720 5.300100e+02 5.793800e+02 +7 8721 -1.263350e+03 1.015020e+03 +10 8721 -1.610800e+03 2.763401e+02 +19 8721 7.312000e+01 1.012890e+03 +7 8722 5.610999e+01 9.035999e+01 +16 8722 3.651001e+01 1.428100e+02 +7 8723 1.315700e+03 1.430200e+02 +18 8723 3.117500e+02 -1.347400e+02 +20 8723 2.741300e+02 -3.087500e+02 +7 8724 1.887000e+02 1.632400e+02 +12 8724 -9.250200e+02 -6.795200e+02 +7 8725 -1.149580e+03 1.674199e+02 +15 8725 3.830400e+02 3.528998e+01 +19 8725 -3.939100e+02 1.298900e+02 +7 8726 -1.156810e+03 1.674900e+02 +15 8726 3.790300e+02 3.541998e+01 +7 8727 1.656000e+02 1.730601e+02 +12 8727 -9.479000e+02 -6.697200e+02 +7 8728 -1.103030e+03 1.993800e+02 +19 8728 2.203300e+02 6.352002e+01 +7 8729 -1.103030e+03 1.993800e+02 +19 8729 2.203300e+02 6.352002e+01 +7 8730 1.153450e+03 2.200901e+02 +12 8730 3.280029e+00 -6.190601e+02 +7 8731 1.153450e+03 2.200901e+02 +18 8731 2.085601e+02 -8.133997e+01 +7 8732 -8.855800e+02 2.255901e+02 +15 8732 7.583400e+02 7.702002e+01 +7 8733 -8.004300e+02 2.280701e+02 +10 8733 -1.220530e+03 -4.822600e+02 +11 8733 -9.093300e+02 -1.170001e+01 +15 8733 8.323700e+02 7.890002e+01 +7 8734 -8.085400e+02 2.283700e+02 +16 8734 -3.794200e+02 2.423900e+02 +7 8735 -1.020260e+03 2.297300e+02 +15 8735 6.512000e+02 8.107001e+01 +7 8736 1.046430e+03 2.390200e+02 +12 8736 -9.180005e+01 -6.031700e+02 +7 8737 -7.933600e+02 2.457500e+02 +10 8737 -1.212570e+03 -4.650000e+02 +7 8738 -9.876600e+02 2.460100e+02 +14 8738 -1.417900e+02 1.921900e+02 +16 8738 -5.169400e+02 2.510500e+02 +7 8739 -9.764400e+02 2.463700e+02 +15 8739 6.865400e+02 9.278998e+01 +7 8740 -9.842900e+02 2.500100e+02 +15 8740 6.795699e+02 9.575000e+01 +16 8740 -5.144700e+02 2.539800e+02 +7 8741 -1.118410e+03 2.504199e+02 +10 8741 -1.530460e+03 -4.561700e+02 +7 8742 -7.755800e+02 2.509600e+02 +10 8742 -1.198550e+03 -4.603600e+02 +7 8743 -1.146170e+03 2.527900e+02 +19 8743 -3.709500e+02 2.532300e+02 +7 8744 -1.048010e+03 2.530200e+02 +19 8744 2.912200e+02 1.304000e+02 +7 8745 1.675900e+02 2.533201e+02 +18 8745 -5.283800e+02 -5.266003e+01 +7 8746 -1.099920e+03 2.539399e+02 +15 8746 5.919800e+02 9.864001e+01 +7 8747 1.046820e+03 2.550500e+02 +17 8747 -6.243400e+02 2.557900e+02 +7 8748 -1.051860e+03 2.554199e+02 +19 8748 2.857800e+02 1.333600e+02 +7 8749 -1.063250e+03 2.560901e+02 +19 8749 2.731899e+02 1.339700e+02 +7 8750 -1.076480e+03 2.564399e+02 +19 8750 2.571600e+02 1.342200e+02 +7 8751 -1.076480e+03 2.564399e+02 +19 8751 2.571600e+02 1.342200e+02 +7 8752 1.050120e+03 2.569500e+02 +12 8752 -8.882996e+01 -5.870100e+02 +13 8752 1.408830e+03 1.245800e+02 +17 8752 -6.152900e+02 2.630100e+02 +18 8752 1.377500e+02 -5.546997e+01 +7 8753 -1.201800e+03 2.569800e+02 +15 8753 5.222200e+02 1.007300e+02 +19 8753 1.096200e+02 1.332300e+02 +7 8754 1.739100e+02 2.605200e+02 +12 8754 -9.375000e+02 -5.805900e+02 +18 8754 -5.255600e+02 -4.659998e+01 +20 8754 -4.458700e+02 -2.388300e+02 +7 8755 1.739100e+02 2.605200e+02 +12 8755 -9.375000e+02 -5.805900e+02 +18 8755 -5.255600e+02 -4.659998e+01 +7 8756 1.461899e+02 2.644099e+02 +12 8756 -9.657900e+02 -5.768101e+02 +7 8757 1.075650e+03 2.669700e+02 +12 8757 -6.632996e+01 -5.772000e+02 +7 8758 2.565300e+02 2.676200e+02 +12 8758 -8.569000e+02 -5.718900e+02 +7 8759 2.904200e+02 3.006799e+02 +13 8759 -1.619450e+03 3.495901e+02 +7 8760 1.088140e+03 3.086100e+02 +12 8760 -5.681995e+01 -5.365000e+02 +7 8761 -7.281800e+02 3.129000e+02 +15 8761 9.094200e+02 1.451200e+02 +19 8761 7.562700e+02 1.970400e+02 +7 8762 -7.949400e+02 3.131500e+02 +19 8762 6.353999e+02 2.062300e+02 +7 8763 -8.774300e+02 3.305400e+02 +15 8763 7.673600e+02 1.572500e+02 +7 8764 1.073100e+03 3.317300e+02 +12 8764 -6.955005e+01 -5.176100e+02 +7 8765 -9.148300e+02 3.408000e+02 +15 8765 7.364200e+02 1.648700e+02 +19 8765 4.630400e+02 2.426500e+02 +7 8766 -8.406700e+02 3.476799e+02 +19 8766 5.704200e+02 2.511000e+02 +7 8767 -8.929200e+02 3.503700e+02 +15 8767 7.550000e+02 1.727100e+02 +19 8767 4.941600e+02 2.548201e+02 +7 8768 -1.135550e+03 3.563500e+02 +19 8768 1.882300e+02 2.560601e+02 +7 8769 -7.878100e+02 3.568700e+02 +15 8769 8.468900e+02 1.793300e+02 +7 8770 -7.987800e+02 3.570300e+02 +19 8770 6.302500e+02 2.629000e+02 +7 8771 -7.377800e+02 3.598301e+02 +14 8771 1.069000e+01 2.483400e+02 +7 8772 -8.872100e+02 3.634500e+02 +15 8772 7.601100e+02 1.829900e+02 +7 8773 -9.328700e+02 3.653600e+02 +14 8773 -1.060400e+02 2.603400e+02 +7 8774 4.116300e+02 3.678000e+02 +12 8774 -7.184800e+02 -4.594200e+02 +7 8775 -9.843100e+02 3.681500e+02 +16 8775 -5.171000e+02 3.387000e+02 +7 8776 -7.500400e+02 3.809299e+02 +19 8776 7.105100e+02 2.907800e+02 +7 8777 1.244460e+03 3.896699e+02 +12 8777 8.027002e+01 -4.630000e+02 +7 8778 2.565200e+02 3.896699e+02 +12 8778 -8.539500e+02 -4.494900e+02 +7 8779 8.639600e+02 3.956500e+02 +12 8779 -2.636500e+02 -4.516500e+02 +7 8780 -3.411400e+02 4.161400e+02 +16 8780 3.510010e+00 3.903800e+02 +19 8780 1.345290e+03 3.342800e+02 +7 8781 -3.736100e+02 4.163700e+02 +16 8781 -1.760999e+01 3.907400e+02 +7 8782 -3.766200e+02 4.264199e+02 +19 8782 1.300090e+03 3.379900e+02 +7 8783 -4.784200e+02 4.303800e+02 +19 8783 1.173040e+03 3.268800e+02 +7 8784 -8.824200e+02 4.316200e+02 +19 8784 6.307500e+02 3.480901e+02 +7 8785 -8.824200e+02 4.316200e+02 +19 8785 5.101500e+02 3.583101e+02 +7 8786 -9.361500e+02 4.329600e+02 +15 8786 6.307100e+02 2.355800e+02 +7 8787 -8.794600e+02 4.351200e+02 +15 8787 7.677200e+02 2.378100e+02 +19 8787 5.139399e+02 3.632300e+02 +7 8788 -7.702800e+02 4.361100e+02 +15 8788 8.650699e+02 2.417500e+02 +7 8789 -7.960900e+02 4.408800e+02 +10 8789 -1.203770e+03 -2.770300e+02 +16 8789 -3.721600e+02 3.968600e+02 +20 8789 -1.131970e+03 -1.084100e+02 +7 8790 -8.365100e+02 4.451200e+02 +14 8790 -4.723001e+01 3.040100e+02 +15 8790 8.044399e+02 2.468800e+02 +19 8790 5.759500e+02 3.763401e+02 +7 8791 -6.045500e+02 4.486000e+02 +16 8791 -2.079300e+02 3.989500e+02 +19 8791 9.962200e+02 3.180300e+02 +7 8792 -7.852100e+02 4.490801e+02 +10 8792 -1.194030e+03 -2.700601e+02 +15 8792 8.517200e+02 2.512400e+02 +19 8792 6.532700e+02 3.798500e+02 +7 8793 1.064610e+03 4.494900e+02 +17 8793 -5.930000e+02 7.046500e+02 +7 8794 1.274020e+03 4.531000e+02 +12 8794 9.906995e+01 -3.902200e+02 +18 8794 2.699800e+02 9.879004e+01 +7 8795 1.274020e+03 4.531000e+02 +12 8795 9.906995e+01 -3.902200e+02 +18 8795 2.699800e+02 9.879004e+01 +20 8795 2.353400e+02 -1.082100e+02 +7 8796 -8.402600e+02 4.551200e+02 +10 8796 -1.243180e+03 -2.626500e+02 +15 8796 8.019100e+02 2.541200e+02 +7 8797 -6.834700e+02 4.560400e+02 +10 8797 -1.117930e+03 -2.658300e+02 +7 8798 -1.055890e+03 4.589900e+02 +19 8798 2.851899e+02 3.861100e+02 +7 8799 -8.867400e+02 4.605100e+02 +15 8799 7.611300e+02 2.569500e+02 +19 8799 5.042900e+02 3.949800e+02 +7 8800 -8.867400e+02 4.605100e+02 +15 8800 7.611300e+02 2.569500e+02 +19 8800 5.042900e+02 3.949800e+02 +7 8801 -8.918300e+02 4.607500e+02 +10 8801 -1.290420e+03 -2.559399e+02 +19 8801 4.979500e+02 3.949800e+02 +7 8802 -8.918300e+02 4.607500e+02 +10 8802 -1.290420e+03 -2.559399e+02 +15 8802 7.582000e+02 2.568700e+02 +19 8802 4.979500e+02 3.949800e+02 +20 8802 -1.193530e+03 -9.600000e+01 +7 8803 -9.334300e+02 4.672900e+02 +15 8803 7.247100e+02 2.604200e+02 +16 8803 -4.795700e+02 4.122000e+02 +19 8803 4.419500e+02 4.018000e+02 +7 8804 -9.999400e+02 4.706400e+02 +15 8804 6.718000e+02 2.610601e+02 +7 8805 -1.125950e+03 4.723101e+02 +19 8805 2.016801e+02 3.986500e+02 +7 8806 -3.233500e+02 4.779800e+02 +19 8806 1.367070e+03 4.170400e+02 +7 8807 -6.552100e+02 4.906200e+02 +19 8807 9.760701e+02 3.723101e+02 +7 8808 -3.825100e+02 4.978900e+02 +19 8808 1.290470e+03 4.313000e+02 +7 8809 -8.293800e+02 5.051100e+02 +10 8809 -1.230650e+03 -2.146200e+02 +7 8810 -6.165100e+02 5.070400e+02 +19 8810 1.018310e+03 3.987700e+02 +7 8811 1.154900e+03 5.095200e+02 +12 8811 -8.599976e+00 -3.336200e+02 +13 8811 1.582510e+03 1.057930e+03 +17 8811 -6.800100e+02 8.310800e+02 +7 8812 -5.416300e+02 5.169099e+02 +10 8812 -1.016360e+03 -2.135000e+02 +7 8813 -5.328400e+02 5.185901e+02 +20 8813 -1.026350e+03 -2.853003e+01 +7 8814 -5.328400e+02 5.185901e+02 +10 8814 -1.039110e+03 -2.165699e+02 +19 8814 1.077230e+03 4.167900e+02 +7 8815 -8.839500e+02 5.213700e+02 +15 8815 7.654399e+02 3.032700e+02 +19 8815 5.096500e+02 4.721000e+02 +7 8816 -1.123750e+03 5.212700e+02 +19 8816 2.043800e+02 4.581599e+02 +7 8817 -5.121200e+02 5.255200e+02 +19 8817 1.133470e+03 4.415200e+02 +7 8818 -5.073000e+02 5.301500e+02 +20 8818 -1.002700e+03 -2.171997e+01 +7 8819 -4.153500e+02 5.413500e+02 +16 8819 -4.620001e+01 4.805000e+02 +7 8820 -1.100810e+03 5.430500e+02 +19 8820 2.318800e+02 4.862200e+02 +7 8821 -1.055699e+02 5.441300e+02 +16 8821 1.610900e+02 4.934700e+02 +7 8822 8.686101e+02 5.504700e+02 +12 8822 -2.731200e+02 -2.870400e+02 +7 8823 -3.299600e+02 5.518201e+02 +14 8823 2.463400e+02 3.346000e+02 +7 8824 2.000400e+02 5.534700e+02 +18 8824 -5.049500e+02 1.861400e+02 +7 8825 -7.490100e+02 5.539900e+02 +19 8825 7.135000e+02 5.115000e+02 +7 8826 -6.200000e+02 5.542800e+02 +19 8826 1.015150e+03 4.551100e+02 +7 8827 1.104770e+03 5.560800e+02 +12 8827 -5.420996e+01 -2.894000e+02 +7 8828 -4.869400e+02 5.608101e+02 +16 8828 -9.281000e+01 4.933500e+02 +7 8829 1.070880e+03 5.644100e+02 +12 8829 -8.504004e+01 -2.803700e+02 +7 8830 -9.950800e+02 5.672800e+02 +19 8830 3.631400e+02 5.242300e+02 +7 8831 -1.837300e+02 5.758500e+02 +16 8831 1.091600e+02 5.145400e+02 +7 8832 -3.341200e+02 5.793300e+02 +19 8832 1.364070e+03 5.416300e+02 +7 8833 -7.553400e+02 5.848400e+02 +16 8833 -3.390200e+02 5.029900e+02 +19 8833 7.040500e+02 5.507200e+02 +7 8834 -1.356970e+03 5.866899e+02 +15 8834 4.256300e+02 3.321300e+02 +19 8834 -4.194995e+01 5.130400e+02 +7 8835 -6.397998e+01 5.892800e+02 +16 8835 2.014800e+02 5.289200e+02 +7 8836 -8.822600e+02 5.989000e+02 +10 8836 -1.271750e+03 -1.244200e+02 +15 8836 7.673800e+02 3.630000e+02 +19 8836 5.118900e+02 5.706600e+02 +7 8837 -4.175000e+01 6.032100e+02 +16 8837 2.196700e+02 5.395200e+02 +7 8838 -4.222998e+01 6.072100e+02 +16 8838 2.187100e+02 5.426500e+02 +7 8839 -8.872500e+02 6.081799e+02 +19 8839 5.053000e+02 5.814500e+02 +7 8840 -1.085680e+03 6.114200e+02 +10 8840 -1.466110e+03 -1.056500e+02 +7 8841 -9.081600e+02 6.179200e+02 +19 8841 4.772300e+02 5.922800e+02 +7 8842 -1.195250e+03 6.254800e+02 +19 8842 1.813500e+02 5.800500e+02 +7 8843 -8.720200e+02 6.279700e+02 +19 8843 5.260000e+02 6.069800e+02 +7 8844 -1.237260e+03 6.298201e+02 +19 8844 8.325000e+01 5.756100e+02 +7 8845 -1.004950e+03 6.315601e+02 +10 8845 -1.385290e+03 -9.004004e+01 +16 8845 -5.356600e+02 5.276200e+02 +20 8845 -1.265240e+03 2.881006e+01 +7 8846 -9.146700e+02 6.372600e+02 +19 8846 4.682700e+02 6.164000e+02 +7 8847 -9.398600e+02 6.401200e+02 +19 8847 4.343900e+02 6.184500e+02 +7 8848 -9.017800e+02 6.402500e+02 +19 8848 4.855900e+02 6.209500e+02 +7 8849 -9.086000e+02 6.413201e+02 +19 8849 4.756500e+02 6.217700e+02 +7 8850 -1.416240e+03 6.418000e+02 +19 8850 -1.004600e+02 5.693600e+02 +7 8851 -1.023500e+03 6.441200e+02 +19 8851 3.260400e+02 6.166000e+02 +7 8852 -1.023500e+03 6.441200e+02 +19 8852 3.260400e+02 6.166000e+02 +7 8853 -8.180800e+02 6.610800e+02 +19 8853 6.074301e+02 6.508201e+02 +7 8854 -4.490000e+02 6.642900e+02 +19 8854 1.220840e+03 6.224100e+02 +7 8855 -1.237640e+03 6.976100e+02 +10 8855 -1.612720e+03 -1.760999e+01 +7 8856 -8.042700e+02 7.080000e+02 +10 8856 -1.195530e+03 -2.693005e+01 +14 8856 -2.154001e+01 4.541500e+02 +19 8856 6.256899e+02 7.093500e+02 +7 8857 -8.839700e+02 7.235500e+02 +10 8857 -1.264390e+03 -9.050049e+00 +15 8857 7.673600e+02 4.566400e+02 +7 8858 -1.116190e+03 7.233600e+02 +19 8858 2.157900e+02 7.030800e+02 +7 8859 -1.206390e+03 7.423700e+02 +10 8859 -1.575940e+03 2.285999e+01 +16 8859 -6.788500e+02 5.991200e+02 +7 8860 -1.206390e+03 7.423700e+02 +10 8860 -1.575940e+03 2.285999e+01 +7 8861 -8.778300e+02 7.528000e+02 +19 8861 5.195000e+02 7.625200e+02 +7 8862 -8.853400e+02 7.576899e+02 +10 8862 -1.263480e+03 2.268994e+01 +7 8863 -9.620200e+02 7.677800e+02 +10 8863 -1.334130e+03 3.550000e+01 +15 8863 7.054700e+02 4.844200e+02 +7 8864 -8.752900e+02 7.722900e+02 +19 8864 5.240200e+02 7.865701e+02 +7 8865 -9.797400e+02 7.727900e+02 +15 8865 6.907000e+02 4.870300e+02 +16 8865 -5.193200e+02 6.305701e+02 +19 8865 3.836801e+02 7.784800e+02 +7 8866 -1.012040e+03 7.748300e+02 +10 8866 -1.380680e+03 4.409998e+01 +7 8867 -1.012040e+03 7.748300e+02 +16 8867 -4.890500e+02 6.270100e+02 +7 8868 -1.021390e+03 7.758400e+02 +10 8868 -1.389300e+03 4.520996e+01 +15 8868 6.594900e+02 4.860800e+02 +20 8868 -1.271040e+03 1.334700e+02 +7 8869 -1.014360e+03 7.789299e+02 +15 8869 6.650100e+02 4.887800e+02 +7 8870 -1.051640e+03 7.790601e+02 +15 8870 6.373400e+02 4.860000e+02 +19 8870 2.969000e+02 7.771500e+02 +7 8871 -1.014440e+03 7.915100e+02 +10 8871 -1.381800e+03 5.943994e+01 +7 8872 -8.028800e+02 7.943000e+02 +10 8872 -1.188840e+03 5.223999e+01 +14 8872 -1.845001e+01 5.032900e+02 +19 8872 6.288899e+02 8.162100e+02 +7 8873 -1.132470e+03 8.147500e+02 +15 8873 5.779200e+02 5.057700e+02 +7 8874 -1.132470e+03 8.147500e+02 +10 8874 -1.494690e+03 8.692004e+01 +15 8874 5.779200e+02 5.057700e+02 +20 8874 -1.352140e+03 1.646500e+02 +7 8875 -1.225450e+03 8.158800e+02 +10 8875 -1.589190e+03 9.262000e+01 +7 8876 -1.236780e+03 8.160900e+02 +10 8876 -1.599810e+03 9.347998e+01 +7 8877 -1.317610e+03 8.188300e+02 +19 8877 2.599976e+00 7.846700e+02 +7 8878 -1.287140e+03 8.193500e+02 +19 8878 3.465002e+01 7.889399e+02 +7 8879 -1.130500e+03 8.222700e+02 +15 8879 5.794000e+02 5.118600e+02 +19 8879 2.019700e+02 8.197600e+02 +7 8880 -8.805500e+02 8.264800e+02 +19 8880 5.154000e+02 8.540800e+02 +7 8881 -8.734400e+02 8.272800e+02 +16 8881 -4.395100e+02 6.745100e+02 +7 8882 -1.113140e+03 8.405800e+02 +15 8882 5.920000e+02 5.262300e+02 +16 8882 -6.171500e+02 6.734399e+02 +7 8883 -9.850800e+02 8.450400e+02 +16 8883 -5.255500e+02 6.823400e+02 +7 8884 -1.117970e+03 8.651200e+02 +10 8884 -1.475270e+03 1.322600e+02 +15 8884 5.892000e+02 5.430900e+02 +7 8885 -1.114470e+03 8.663800e+02 +16 8885 -6.173600e+02 6.918300e+02 +7 8886 -1.207900e+03 8.715500e+02 +15 8886 5.270000e+02 5.404100e+02 +19 8886 1.184399e+02 8.631899e+02 +7 8887 -1.273750e+03 8.853300e+02 +15 8887 4.826400e+02 5.445800e+02 +7 8888 -1.185180e+03 8.930400e+02 +16 8888 -6.688400e+02 7.082600e+02 +7 8889 -7.918600e+02 8.954200e+02 +20 8889 -1.150150e+03 2.327300e+02 +7 8890 -8.110200e+02 9.000300e+02 +16 8890 -3.906000e+02 7.304100e+02 +7 8891 -1.238070e+03 9.051200e+02 +19 8891 8.739001e+01 8.979399e+02 +7 8892 -1.208950e+03 9.239600e+02 +15 8892 5.274200e+02 5.772300e+02 +16 8892 -6.841600e+02 7.285300e+02 +7 8893 2.265400e+02 -6.896997e+01 +19 8893 4.205200e+02 2.195996e+01 +7 8894 1.431200e+02 6.737000e+01 +12 8894 -7.734300e+02 -8.410400e+02 +7 8895 1.956300e+02 1.628600e+02 +12 8895 -9.178600e+02 -6.800200e+02 +7 8896 2.750500e+02 1.756300e+02 +12 8896 -8.422000e+02 -6.637700e+02 +7 8897 -7.958500e+02 1.910500e+02 +16 8897 -3.683400e+02 2.147700e+02 +7 8898 -7.925400e+02 2.244700e+02 +15 8898 8.388400e+02 7.578998e+01 +7 8899 -7.966000e+02 2.244600e+02 +15 8899 8.350200e+02 7.600000e+01 +7 8900 -1.117450e+03 2.539399e+02 +19 8900 2.062100e+02 1.309199e+02 +7 8901 -1.117450e+03 2.539399e+02 +19 8901 2.062100e+02 1.309199e+02 +7 8902 -9.994100e+02 2.593600e+02 +19 8902 3.528500e+02 1.387400e+02 +7 8903 -8.718000e+02 2.654700e+02 +15 8903 7.709100e+02 1.076600e+02 +7 8904 1.264840e+03 2.665901e+02 +12 8904 1.004800e+02 -5.760601e+02 +18 8904 2.860400e+02 -4.773999e+01 +7 8905 8.904299e+02 2.836000e+02 +12 8905 -2.360800e+02 -5.592200e+02 +7 8906 8.937600e+02 2.862500e+02 +12 8906 -2.341300e+02 -5.566400e+02 +7 8907 1.353010e+03 2.874500e+02 +18 8907 3.357000e+02 -2.909998e+01 +7 8908 -7.949600e+02 3.053600e+02 +19 8908 6.354700e+02 1.954900e+02 +7 8909 1.353480e+03 3.087200e+02 +12 8909 1.738500e+02 -5.310601e+02 +7 8910 -7.956200e+02 3.262200e+02 +19 8910 6.353501e+02 2.226300e+02 +7 8911 -1.182330e+03 3.263201e+02 +19 8911 1.309200e+02 2.189199e+02 +7 8912 1.157560e+03 3.337500e+02 +12 8912 5.540039e+00 -5.136801e+02 +7 8913 1.177300e+03 3.342300e+02 +12 8913 2.223999e+01 -5.135500e+02 +7 8914 -9.815300e+02 3.367300e+02 +19 8914 3.743101e+02 2.364900e+02 +7 8915 -1.005280e+03 3.394000e+02 +19 8915 3.437000e+02 2.396599e+02 +7 8916 -8.088700e+02 3.454900e+02 +10 8916 -1.221330e+03 -3.682800e+02 +19 8916 6.163101e+02 2.477100e+02 +7 8917 -7.979100e+02 3.472800e+02 +19 8917 6.309900e+02 2.494000e+02 +7 8918 3.023199e+02 3.505701e+02 +12 8918 -8.146200e+02 -4.850500e+02 +7 8919 -7.687900e+02 3.512700e+02 +10 8919 -1.186400e+03 -3.640100e+02 +7 8920 1.355510e+03 3.525000e+02 +12 8920 1.739200e+02 -4.903800e+02 +7 8921 1.355510e+03 3.525000e+02 +12 8921 1.739200e+02 -4.903800e+02 +7 8922 -1.039970e+03 3.584399e+02 +19 8922 3.016100e+02 2.626400e+02 +7 8923 1.101160e+03 3.834299e+02 +12 8923 -4.633997e+01 -4.670800e+02 +7 8924 1.083910e+03 3.847400e+02 +12 8924 -6.152002e+01 -4.656000e+02 +7 8925 -7.503800e+02 3.896400e+02 +10 8925 -1.169340e+03 -3.268400e+02 +7 8926 -7.503800e+02 3.896400e+02 +10 8926 -1.169340e+03 -3.268400e+02 +7 8927 -7.993400e+02 3.975601e+02 +19 8927 6.306101e+02 3.145801e+02 +7 8928 -7.993400e+02 3.975601e+02 +19 8928 6.305901e+02 3.146100e+02 +7 8929 -8.817000e+02 3.987700e+02 +15 8929 7.651801e+02 2.101500e+02 +19 8929 5.107500e+02 3.161400e+02 +7 8930 -7.558200e+02 4.086300e+02 +19 8930 7.032100e+02 3.250300e+02 +7 8931 -9.894000e+02 4.100701e+02 +15 8931 6.786000e+02 2.159500e+02 +16 8931 -5.208500e+02 3.687800e+02 +7 8932 1.281160e+03 4.148201e+02 +12 8932 1.080100e+02 -4.311700e+02 +7 8933 -8.825500e+02 4.255100e+02 +19 8933 5.097600e+02 3.507300e+02 +7 8934 9.389500e+02 4.270500e+02 +12 8934 -1.918400e+02 -4.254000e+02 +7 8935 -8.759600e+02 4.281599e+02 +19 8935 5.195000e+02 3.543101e+02 +7 8936 9.403601e+02 4.325601e+02 +12 8936 -1.907900e+02 -4.206000e+02 +17 8936 -8.778300e+02 6.796600e+02 +7 8937 -1.102140e+03 4.327200e+02 +19 8937 2.275900e+02 3.515801e+02 +7 8938 -7.645000e+02 4.344600e+02 +19 8938 6.854199e+02 3.605400e+02 +7 8939 -1.123830e+03 4.353900e+02 +19 8939 2.021000e+02 3.532600e+02 +7 8940 -5.992900e+02 4.472900e+02 +19 8940 1.036760e+03 3.284600e+02 +7 8941 -1.041660e+03 4.602500e+02 +19 8941 3.026200e+02 3.886200e+02 +7 8942 -1.042210e+03 4.630500e+02 +19 8942 3.016300e+02 3.925500e+02 +7 8943 2.628800e+02 4.648700e+02 +12 8943 -8.456300e+02 -3.732300e+02 +7 8944 9.133799e+02 4.666000e+02 +12 8944 -2.239900e+02 -3.775500e+02 +7 8945 -9.987300e+02 4.676699e+02 +19 8945 3.560300e+02 3.997500e+02 +7 8946 -1.135690e+03 4.693301e+02 +19 8946 1.898300e+02 3.939000e+02 +7 8947 -1.104910e+03 4.725100e+02 +19 8947 2.234301e+02 4.001400e+02 +7 8948 8.688301e+02 4.812200e+02 +12 8948 -2.726700e+02 -3.532900e+02 +7 8949 1.019690e+03 4.820901e+02 +12 8949 -1.313500e+02 -3.565500e+02 +7 8950 1.008260e+03 4.821300e+02 +12 8950 -1.427000e+02 -3.557800e+02 +7 8951 -4.835600e+02 4.880200e+02 +19 8951 1.166290e+03 4.001599e+02 +7 8952 -3.488500e+02 4.959000e+02 +19 8952 1.334570e+03 4.345400e+02 +7 8953 -3.751600e+02 4.962000e+02 +19 8953 1.300020e+03 4.305901e+02 +7 8954 -3.320400e+02 5.014399e+02 +19 8954 1.355790e+03 4.462300e+02 +7 8955 1.187940e+03 5.029099e+02 +12 8955 2.106006e+01 -3.404399e+02 +7 8956 1.115690e+03 5.053401e+02 +17 8956 -7.640300e+02 8.270800e+02 +7 8957 1.609800e+02 5.055300e+02 +12 8957 -9.419100e+02 -3.344100e+02 +7 8958 1.058050e+03 5.083101e+02 +12 8958 -9.663000e+01 -3.323500e+02 +7 8959 1.129890e+03 5.087700e+02 +13 8959 1.492920e+03 1.058130e+03 +7 8960 -3.986400e+02 5.166400e+02 +19 8960 1.271370e+03 4.527400e+02 +7 8961 9.998501e+02 5.172400e+02 +12 8961 -1.502000e+02 -3.228900e+02 +7 8962 -1.004320e+03 5.251300e+02 +19 8962 3.504100e+02 4.706500e+02 +7 8963 1.028003e+01 5.408201e+02 +16 8963 2.440400e+02 4.941200e+02 +7 8964 -5.305500e+02 5.410500e+02 +19 8964 1.113460e+03 4.572800e+02 +7 8965 -3.622300e+02 5.496300e+02 +19 8965 1.321810e+03 4.994700e+02 +7 8966 -6.881400e+02 5.498900e+02 +19 8966 8.308701e+02 4.941799e+02 +7 8967 -5.862300e+02 5.541500e+02 +19 8967 1.052240e+03 4.609000e+02 +7 8968 1.551700e+02 5.650100e+02 +12 8968 -9.467000e+02 -2.751899e+02 +7 8969 -1.042430e+03 5.674600e+02 +19 8969 3.035100e+02 5.199500e+02 +7 8970 -1.358590e+03 5.726100e+02 +19 8970 -4.435999e+01 4.958301e+02 +7 8971 6.546001e+02 5.745100e+02 +16 8971 5.670601e+02 5.527800e+02 +7 8972 -1.056210e+03 5.752400e+02 +10 8972 -1.440390e+03 -1.408800e+02 +7 8973 -5.325500e+02 5.767500e+02 +19 8973 1.109290e+03 5.015100e+02 +7 8974 -7.531800e+02 5.781200e+02 +19 8974 7.070801e+02 5.418101e+02 +7 8975 -4.007200e+02 5.823800e+02 +19 8975 1.276120e+03 5.328000e+02 +7 8976 -4.978600e+02 5.893400e+02 +19 8976 1.150270e+03 5.255400e+02 +7 8977 -8.847600e+02 5.901000e+02 +19 8977 5.087400e+02 5.586899e+02 +7 8978 -3.825500e+02 5.939500e+02 +19 8978 1.299250e+03 5.507700e+02 +7 8979 -3.815800e+02 5.970200e+02 +19 8979 1.299880e+03 5.546599e+02 +7 8980 -8.251300e+02 6.004000e+02 +19 8980 5.950000e+02 5.723201e+02 +7 8981 -8.041200e+02 6.035100e+02 +19 8981 6.249199e+02 5.773700e+02 +7 8982 -8.490700e+02 6.033500e+02 +19 8982 5.606899e+02 5.763600e+02 +7 8983 -7.108997e+01 6.054500e+02 +12 8983 -1.199490e+03 -2.134700e+02 +7 8984 -7.341400e+02 6.091799e+02 +19 8984 7.353201e+02 5.824600e+02 +7 8985 -9.899700e+02 6.089500e+02 +10 8985 -1.372780e+03 -1.113400e+02 +15 8985 6.812400e+02 3.650000e+02 +16 8985 -5.239600e+02 5.123201e+02 +20 8985 -1.255590e+03 1.275000e+01 +7 8986 -9.417000e+02 6.166700e+02 +19 8986 4.348900e+02 5.864299e+02 +7 8987 -1.009800e+03 6.170601e+02 +19 8987 2.847500e+02 5.853500e+02 +7 8988 -9.445900e+02 6.364200e+02 +19 8988 4.270800e+02 6.134000e+02 +7 8989 -1.295210e+03 6.399900e+02 +19 8989 2.131995e+01 5.813600e+02 +7 8990 -8.028000e+02 6.433500e+02 +19 8990 6.213800e+02 6.309900e+02 +7 8991 -1.114120e+03 6.984600e+02 +19 8991 2.193800e+02 6.740000e+02 +7 8992 -1.199110e+03 6.996500e+02 +15 8992 5.635200e+02 4.217900e+02 +7 8993 -7.941500e+02 7.036000e+02 +19 8993 6.415100e+02 7.039200e+02 +7 8994 -9.100300e+02 7.172900e+02 +10 8994 -1.289570e+03 -1.379004e+01 +7 8995 -1.127810e+03 7.199900e+02 +19 8995 2.029301e+02 6.959200e+02 +7 8996 -8.051100e+02 7.253900e+02 +19 8996 6.224399e+02 7.323800e+02 +7 8997 -8.838700e+02 7.299299e+02 +10 8997 -1.263910e+03 -3.150024e+00 +11 8997 -1.005840e+03 6.268400e+02 +19 8997 5.107000e+02 7.339500e+02 +7 8998 -7.652600e+02 7.370400e+02 +19 8998 6.920000e+02 7.426000e+02 +7 8999 -7.704900e+02 7.395601e+02 +19 8999 6.816201e+02 7.465500e+02 +7 9000 -7.825600e+02 7.444399e+02 +19 9000 6.632500e+02 7.528500e+02 +7 9001 -1.356780e+03 7.904399e+02 +19 9001 -3.594995e+01 7.446100e+02 +7 9002 -1.268270e+03 7.922000e+02 +19 9002 5.358997e+01 7.617000e+02 +7 9003 -1.354080e+03 7.985400e+02 +19 9003 -3.282996e+01 7.545701e+02 +7 9004 -1.255640e+03 8.026100e+02 +10 9004 -1.620800e+03 8.140002e+01 +7 9005 -1.112530e+03 8.040900e+02 +19 9005 2.207000e+02 8.002200e+02 +7 9006 -1.116210e+03 8.043600e+02 +19 9006 2.166600e+02 7.998201e+02 +7 9007 -1.296070e+03 8.090000e+02 +19 9007 2.451001e+01 7.766200e+02 +7 9008 -9.911700e+02 8.106400e+02 +19 9008 3.709000e+02 8.229399e+02 +7 9009 -8.099300e+02 8.280000e+02 +19 9009 6.205500e+02 8.538000e+02 +7 9010 -1.229820e+03 8.721400e+02 +10 9010 -1.587080e+03 1.447100e+02 +7 9011 -1.026210e+03 8.825500e+02 +15 9011 4.472700e+02 5.631300e+02 +7 9012 -1.203580e+03 9.099299e+02 +19 9012 1.235400e+02 9.091899e+02 +7 9013 -1.213640e+03 9.148000e+02 +15 9013 5.230500e+02 5.702000e+02 +19 9013 1.119000e+02 9.129900e+02 +7 9014 -1.076790e+03 9.273000e+02 +10 9014 -1.440290e+03 1.852300e+02 +8 9015 4.938000e+02 1.229300e+02 +16 9015 7.513600e+02 3.840300e+02 +8 9016 -5.557500e+02 -1.448800e+02 +16 9016 8.820500e+02 1.533300e+02 +8 9017 2.106500e+02 -3.863000e+01 +16 9017 6.838600e+02 2.809200e+02 +8 9018 7.973199e+02 2.122400e+02 +16 9018 9.572200e+02 3.467600e+02 +8 9019 4.576000e+02 2.263300e+02 +16 9019 7.364900e+02 4.293900e+02 +8 9020 4.576000e+02 2.263300e+02 +16 9020 7.364900e+02 4.293900e+02 +8 9021 3.401200e+02 -1.186700e+02 +16 9021 7.252400e+02 2.567600e+02 +8 9022 6.207000e+02 7.830017e+00 +16 9022 8.038600e+02 3.370400e+02 +8 9023 6.043900e+02 2.628003e+01 +16 9023 7.958700e+02 3.475000e+02 +8 9024 4.771000e+02 1.283200e+02 +16 9024 7.464301e+02 3.844700e+02 +8 9025 9.810601e+02 -1.216800e+02 +12 9025 -1.587200e+02 -6.600601e+02 +18 9025 8.191003e+01 -1.125500e+02 +20 9025 7.792004e+01 -2.915800e+02 +8 9026 9.810601e+02 -1.216800e+02 +12 9026 -1.587200e+02 -6.600601e+02 +18 9026 8.191003e+01 -1.125500e+02 +20 9026 7.792004e+01 -2.915800e+02 +8 9027 6.158900e+02 7.345001e+01 +16 9027 8.007300e+02 3.691500e+02 +8 9028 6.568700e+02 7.877002e+01 +16 9028 8.210900e+02 3.718000e+02 +8 9029 9.576300e+02 1.125100e+02 +20 9029 7.145996e+01 -2.272900e+02 +8 9030 9.485000e+02 -1.112200e+02 +12 9030 -1.726700e+02 -6.552900e+02 +17 9030 -8.212900e+02 9.606995e+01 +8 9031 1.966600e+02 5.479980e+00 +16 9031 6.789100e+02 2.989299e+02 +8 9032 4.954399e+02 1.108500e+02 +16 9032 7.552800e+02 3.771300e+02 +8 9033 9.830900e+02 2.951600e+02 +20 9033 7.902002e+01 -1.776500e+02 +8 9034 2.419100e+02 4.238000e+02 +16 9034 6.762300e+02 4.844299e+02 +8 9035 8.701899e+02 5.377002e+01 +12 9035 -2.038101e+02 -5.867400e+02 +8 9036 8.701899e+02 5.377002e+01 +17 9036 -9.058900e+02 2.616400e+02 +8 9037 5.952500e+02 9.284998e+01 +16 9037 7.914301e+02 3.770300e+02 +8 9038 2.861100e+02 2.707300e+02 +16 9038 6.968700e+02 4.180701e+02 +8 9039 8.820100e+02 2.880500e+02 +17 9039 -8.856800e+02 4.970601e+02 +8 9040 9.318400e+02 4.073201e+02 +17 9040 -8.375700e+02 6.141400e+02 +8 9041 6.126500e+02 9.345001e+01 +16 9041 7.997200e+02 3.785800e+02 +8 9042 4.784800e+02 1.116300e+02 +16 9042 7.471600e+02 3.767100e+02 +8 9043 9.425200e+02 1.201000e+02 +12 9043 -1.738101e+02 -5.619200e+02 +17 9043 -8.268400e+02 3.251599e+02 +8 9044 4.962900e+02 1.631500e+02 +16 9044 7.542900e+02 4.011799e+02 +8 9045 7.936500e+02 1.729900e+02 +16 9045 9.547400e+02 3.352300e+02 +8 9046 9.600800e+02 2.277800e+02 +12 9046 -1.657500e+02 -5.192500e+02 +8 9047 9.675400e+02 -1.248100e+02 +17 9047 -7.940700e+02 8.160999e+01 +8 9048 9.675400e+02 -1.248100e+02 +12 9048 -1.647100e+02 -6.610000e+02 +17 9048 -7.940700e+02 8.160999e+01 +8 9049 9.135100e+02 9.451001e+01 +17 9049 -8.549500e+02 3.006100e+02 +9 9050 9.181201e+02 7.154004e+01 +12 9050 1.122500e+02 -6.230400e+02 +20 9050 2.571899e+02 -2.683400e+02 +9 9051 6.680801e+02 7.809998e+01 +12 9051 -8.431995e+01 -6.161899e+02 +18 9051 1.412000e+02 -7.754004e+01 +9 9052 -1.178700e+02 3.117700e+02 +11 9052 5.053700e+02 2.431300e+02 +13 9052 -1.013750e+03 6.064600e+02 +18 9052 -3.349200e+02 7.579004e+01 +20 9052 -2.828000e+02 -1.343199e+02 +9 9053 -8.699000e+02 4.349800e+02 +11 9053 -1.916500e+02 3.580601e+02 +18 9053 -8.135400e+02 1.615601e+02 +9 9054 -1.025860e+03 3.234900e+02 +11 9054 -3.403400e+02 2.517000e+02 +18 9054 -9.127700e+02 9.317993e+01 +20 9054 -7.818200e+02 -1.182200e+02 +9 9055 -1.067830e+03 3.407100e+02 +11 9055 -3.782700e+02 2.674000e+02 +16 9055 4.268005e+01 4.042300e+02 +9 9056 -1.067830e+03 3.407100e+02 +11 9056 -3.782700e+02 2.674000e+02 +16 9056 4.268005e+01 4.042300e+02 +9 9057 5.831699e+02 4.510100e+02 +12 9057 -1.176500e+02 -3.263199e+02 +20 9057 8.591003e+01 -6.430005e+01 +9 9058 -1.280250e+03 5.885701e+02 +11 9058 -5.865000e+02 5.017100e+02 +14 9058 2.090300e+02 3.593600e+02 +9 9059 -4.964301e+02 -4.470000e+02 +18 9059 -6.620000e+02 -3.996400e+02 +9 9060 8.737500e+02 7.039001e+01 +12 9060 7.431995e+01 -6.258800e+02 +18 9060 2.645300e+02 -8.879004e+01 +20 9060 2.339301e+02 -2.695000e+02 +9 9061 1.083400e+03 2.110801e+02 +10 9061 7.349800e+02 -4.094100e+02 +18 9061 3.965601e+02 -4.739990e+00 +20 9061 3.455601e+02 -1.955900e+02 +9 9062 -9.650100e+02 2.395500e+02 +11 9062 -2.825700e+02 1.738000e+02 +18 9062 -8.757900e+02 4.263000e+01 +9 9063 -9.724500e+02 3.242200e+02 +11 9063 -2.924400e+02 2.461900e+02 +18 9063 -8.812100e+02 8.925000e+01 +9 9064 -9.146100e+02 3.426400e+02 +11 9064 -2.352900e+02 2.719100e+02 +18 9064 -8.426100e+02 1.034399e+02 +9 9065 -1.024670e+03 4.110000e+02 +11 9065 -3.386300e+02 3.340600e+02 +18 9065 -9.085900e+02 1.500400e+02 +9 9066 6.833201e+02 4.217600e+02 +12 9066 -4.204004e+01 -3.546899e+02 +20 9066 1.394200e+02 -8.237000e+01 +9 9067 -8.283800e+02 5.721599e+02 +11 9067 -1.571200e+02 4.902300e+02 +12 9067 -1.259410e+03 -2.048500e+02 +14 9067 3.748400e+02 3.782100e+02 +16 9067 1.484000e+02 5.432400e+02 +20 9067 -6.733400e+02 1.384003e+01 +9 9068 -8.485600e+02 -3.933500e+02 +20 9068 -8.055100e+02 -5.223800e+02 +9 9069 7.652900e+02 -1.370996e+01 +12 9069 -1.172998e+01 -6.925200e+02 +9 9070 -1.206600e+02 2.442700e+02 +11 9070 4.995000e+02 1.785600e+02 +13 9070 -1.031790e+03 4.350100e+02 +18 9070 -3.388900e+02 3.232996e+01 +20 9070 -2.866100e+02 -1.691801e+02 +9 9071 7.238301e+02 2.555400e+02 +17 9071 -5.203500e+02 5.128000e+02 +9 9072 -9.558200e+02 2.979000e+02 +11 9072 -2.736800e+02 2.289500e+02 +18 9072 -8.683500e+02 7.732007e+01 +9 9073 -1.185000e+03 3.707500e+02 +11 9073 -4.909300e+02 2.976200e+02 +14 9073 2.311900e+02 2.799500e+02 +9 9074 5.853799e+02 4.223101e+02 +12 9074 -1.225601e+02 -3.476500e+02 +9 9075 6.163301e+02 4.299000e+02 +12 9075 -9.147998e+01 -3.461000e+02 +20 9075 1.031100e+02 -7.753003e+01 +9 9076 6.452000e+02 4.603700e+02 +17 9076 -8.278700e+02 8.675000e+02 +20 9076 1.180400e+02 -6.313000e+01 +9 9077 -8.711600e+02 5.426899e+02 +11 9077 -1.943100e+02 4.628700e+02 +18 9077 -8.112200e+02 2.285801e+02 +9 9078 -9.285600e+02 5.485500e+02 +14 9078 3.324600e+02 3.641400e+02 +18 9078 -8.478200e+02 2.315100e+02 +9 9079 -5.334000e+02 5.585100e+02 +11 9079 1.216500e+02 4.793000e+02 +18 9079 -5.965600e+02 2.365500e+02 +9 9080 -2.078800e+02 1.883997e+01 +11 9080 4.312100e+02 -3.852002e+01 +12 9080 -7.624300e+02 -6.587400e+02 +9 9081 -2.089100e+02 8.817004e+01 +11 9081 4.291700e+02 3.063000e+01 +20 9081 -3.414500e+02 -2.524200e+02 +9 9082 6.381699e+02 1.642600e+02 +12 9082 -1.108900e+02 -5.482000e+02 +13 9082 1.322530e+03 2.720400e+02 +17 9082 -6.684000e+02 3.491899e+02 +9 9083 7.931101e+02 2.399700e+02 +12 9083 9.270020e+00 -4.936500e+02 +18 9083 2.155400e+02 1.921997e+01 +9 9084 -1.181030e+03 2.508401e+02 +11 9084 -4.864300e+02 1.839500e+02 +18 9084 -1.009510e+03 5.177002e+01 +20 9084 -8.676700e+02 -1.551000e+02 +9 9085 -9.591000e+02 2.620500e+02 +11 9085 -2.762800e+02 1.948300e+02 +18 9085 -8.715100e+02 5.582007e+01 +9 9086 -1.127560e+03 2.875400e+02 +11 9086 -4.362900e+02 2.191100e+02 +18 9086 -9.754000e+02 7.401001e+01 +9 9087 -1.664600e+02 2.913800e+02 +11 9087 4.676400e+02 2.255000e+02 +13 9087 -1.221640e+03 6.692800e+02 +9 9088 -9.333900e+02 3.159500e+02 +11 9088 -2.520500e+02 2.457700e+02 +18 9088 -8.546900e+02 8.797998e+01 +20 9088 -7.321000e+02 -1.234600e+02 +9 9089 -9.333900e+02 3.159500e+02 +11 9089 -2.520500e+02 2.457700e+02 +18 9089 -8.546900e+02 8.797998e+01 +20 9089 -7.321000e+02 -1.234600e+02 +9 9090 1.044500e+03 3.604800e+02 +12 9090 2.569600e+02 -4.013600e+02 +18 9090 3.799900e+02 8.915991e+01 +20 9090 3.269600e+02 -1.169200e+02 +9 9091 -1.260700e+03 3.701300e+02 +19 9091 1.267530e+03 3.594900e+02 +9 9092 -1.215230e+03 3.973700e+02 +16 9092 -1.909003e+01 4.231899e+02 +20 9092 -8.832200e+02 -7.860999e+01 +9 9093 -1.355720e+03 4.083301e+02 +11 9093 -6.523900e+02 3.322200e+02 +16 9093 -7.427002e+01 4.303700e+02 +19 9093 1.198510e+03 3.852900e+02 +20 9093 -9.589300e+02 -6.797998e+01 +9 9094 6.188000e+02 4.889399e+02 +12 9094 -8.967004e+01 -3.020300e+02 +17 9094 -8.749200e+02 9.184600e+02 +9 9095 -1.076410e+03 5.234399e+02 +16 9095 6.843994e+01 5.001200e+02 +9 9096 5.963899e+02 -5.797600e+02 +18 9096 1.302002e+01 -5.229600e+02 +9 9097 5.963899e+02 -5.797600e+02 +18 9097 1.302002e+01 -5.229600e+02 +9 9098 -5.576200e+02 -4.112900e+02 +20 9098 -5.857000e+02 -5.281400e+02 +9 9099 9.560300e+02 -8.290039e+00 +12 9099 1.510300e+02 -6.880200e+02 +18 9099 3.154500e+02 -1.371200e+02 +20 9099 2.779600e+02 -3.109700e+02 +9 9100 -9.692004e+01 1.310100e+02 +11 9100 5.218600e+02 7.026001e+01 +18 9100 -3.253199e+02 -3.804004e+01 +20 9100 -2.752500e+02 -2.297600e+02 +9 9101 -1.252450e+03 3.154900e+02 +11 9101 -5.539700e+02 2.452600e+02 +14 9101 2.057400e+02 2.554600e+02 +9 9102 6.137600e+02 3.177600e+02 +12 9102 -1.287900e+02 -4.321600e+02 +9 9103 -1.129780e+03 3.498000e+02 +16 9103 1.604004e+01 4.062600e+02 +9 9104 -1.071090e+03 3.511300e+02 +11 9104 -3.835600e+02 2.785200e+02 +14 9104 2.727500e+02 2.747300e+02 +9 9105 -1.524399e+02 3.805000e+02 +13 9105 -1.108750e+03 8.287000e+02 +9 9106 5.843201e+02 3.984900e+02 +12 9106 -1.173199e+02 -3.704600e+02 +20 9106 8.607996e+01 -9.391003e+01 +9 9107 5.843201e+02 3.984900e+02 +12 9107 -1.173199e+02 -3.704600e+02 +20 9107 8.607996e+01 -9.391003e+01 +9 9108 -1.184240e+03 4.250901e+02 +11 9108 -4.891300e+02 3.490200e+02 +18 9108 -1.007290e+03 1.598500e+02 +9 9109 -1.049250e+03 4.519900e+02 +11 9109 -3.618900e+02 3.734900e+02 +18 9109 -9.229400e+02 1.749700e+02 +9 9110 -1.391250e+03 4.863000e+02 +11 9110 -6.871000e+02 4.081600e+02 +14 9110 1.621000e+02 3.196400e+02 +18 9110 -1.137360e+03 2.040601e+02 +9 9111 -8.516100e+02 5.963301e+02 +14 9111 3.646500e+02 3.849600e+02 +9 9112 -9.465000e+02 -5.393800e+02 +20 9112 -8.784400e+02 -6.075100e+02 +9 9113 -4.555005e+01 -1.050900e+02 +13 9113 -1.227800e+03 -6.637000e+01 +9 9114 -3.220300e+02 -3.289001e+01 +12 9114 -8.762500e+02 -6.968900e+02 +9 9115 9.781699e+02 -1.267004e+01 +12 9115 1.681000e+02 -6.926300e+02 +9 9116 9.856799e+02 4.398999e+01 +12 9116 1.736700e+02 -6.460900e+02 +18 9116 3.339399e+02 -1.051100e+02 +9 9117 9.856799e+02 4.398999e+01 +12 9117 1.736700e+02 -6.460900e+02 +18 9117 3.339399e+02 -1.051100e+02 +9 9118 -4.675800e+02 1.443900e+02 +12 9118 -9.943400e+02 -5.524399e+02 +9 9119 7.408601e+02 1.594900e+02 +17 9119 -4.973000e+02 3.326500e+02 +9 9120 1.014340e+03 1.793800e+02 +10 9120 7.009399e+02 -4.317600e+02 +18 9120 3.508000e+02 -2.268994e+01 +9 9121 7.846599e+02 2.074600e+02 +12 9121 7.239990e+00 -5.199301e+02 +9 9122 3.343900e+02 2.154500e+02 +12 9122 -5.210600e+02 -5.078300e+02 +18 9122 -9.447998e+01 9.329956e+00 +20 9122 -6.821997e+01 -1.893000e+02 +9 9123 -1.184720e+03 2.366300e+02 +11 9123 -4.893900e+02 1.715600e+02 +20 9123 -8.699800e+02 -1.625000e+02 +9 9124 3.824900e+02 2.646699e+02 +12 9124 -4.829100e+02 -4.697500e+02 +9 9125 5.457000e+02 2.681799e+02 +17 9125 2.174600e+02 8.729700e+02 +20 9125 4.493005e+01 -1.625800e+02 +9 9126 -9.417500e+02 2.732900e+02 +11 9126 -2.602900e+02 2.055200e+02 +18 9126 -8.604400e+02 6.215991e+01 +9 9127 -1.369820e+03 3.277800e+02 +11 9127 -6.653300e+02 2.563600e+02 +14 9127 1.668800e+02 2.571000e+02 +18 9127 -1.125350e+03 1.026500e+02 +9 9128 6.230601e+02 3.315400e+02 +13 9128 1.273910e+03 8.002500e+02 +9 9129 8.967000e+02 3.483401e+02 +12 9129 1.086899e+02 -4.127800e+02 +18 9129 2.827500e+02 8.183008e+01 +20 9129 2.476000e+02 -1.228600e+02 +9 9130 6.883601e+02 4.727000e+02 +12 9130 -3.671997e+01 -3.149700e+02 +9 9131 -9.335700e+02 4.796699e+02 +11 9131 -2.518900e+02 4.011700e+02 +14 9131 3.276000e+02 3.364900e+02 +18 9131 -8.512400e+02 1.907000e+02 +9 9132 -5.787100e+02 5.608700e+02 +11 9132 8.066003e+01 4.829600e+02 +18 9132 -6.264200e+02 2.366699e+02 +9 9133 -7.283600e+02 5.690601e+02 +11 9133 -6.175000e+01 4.878800e+02 +20 9133 -6.132200e+02 1.183002e+01 +9 9134 -1.216180e+03 6.209199e+02 +11 9134 -5.281200e+02 5.338300e+02 +18 9134 -1.022490e+03 2.831500e+02 +19 9134 1.362450e+03 5.866100e+02 +20 9134 -8.765300e+02 4.463000e+01 +9 9135 9.859900e+02 -2.042004e+01 +12 9135 1.739900e+02 -6.971200e+02 +18 9135 3.335900e+02 -1.447200e+02 +20 9135 2.934399e+02 -3.177300e+02 +9 9136 9.859900e+02 -2.042004e+01 +12 9136 1.739900e+02 -6.971200e+02 +18 9136 3.335900e+02 -1.447200e+02 +20 9136 2.934399e+02 -3.177300e+02 +9 9137 7.012900e+02 -9.880005e+00 +12 9137 -6.181006e+01 -6.883400e+02 +9 9138 3.383300e+02 1.303003e+01 +17 9138 -1.993400e+02 2.742700e+02 +9 9139 3.383300e+02 1.303003e+01 +17 9139 -1.993400e+02 2.742700e+02 +9 9140 -2.531700e+02 1.381006e+01 +11 9140 3.893400e+02 -4.132001e+01 +20 9140 -3.671899e+02 -2.917800e+02 +9 9141 -2.368600e+02 1.528003e+01 +11 9141 4.046300e+02 -4.001001e+01 +18 9141 -4.220699e+02 -1.080300e+02 +20 9141 -3.570800e+02 -2.912600e+02 +9 9142 9.767100e+02 1.222300e+02 +12 9142 1.671300e+02 -5.854700e+02 +18 9142 3.293300e+02 -5.718005e+01 +9 9143 6.889800e+02 1.567700e+02 +13 9143 1.482890e+03 2.416000e+02 +9 9144 -1.906600e+02 2.159500e+02 +11 9144 4.448101e+02 1.533400e+02 +18 9144 -3.888500e+02 1.597998e+01 +20 9144 -3.288199e+02 -1.841500e+02 +9 9145 9.053601e+02 2.364000e+02 +12 9145 9.806006e+01 -4.988700e+02 +18 9145 2.852000e+02 1.323999e+01 +9 9146 -1.124120e+03 2.495000e+02 +11 9146 -4.320100e+02 1.826900e+02 +18 9146 -9.748400e+02 5.020996e+01 +9 9147 3.158900e+02 2.563401e+02 +17 9147 -2.361000e+02 8.639399e+02 +9 9148 4.491600e+02 2.582700e+02 +20 9148 -3.794995e+01 -1.675300e+02 +9 9149 9.268000e+02 2.877100e+02 +12 9149 1.146600e+02 -4.591200e+02 +9 9150 -1.108230e+03 3.006500e+02 +11 9150 -4.171800e+02 2.309700e+02 +18 9150 -9.633600e+02 8.176001e+01 +9 9151 -1.210840e+03 3.030701e+02 +11 9151 -5.147700e+02 2.318000e+02 +18 9151 -1.026850e+03 8.323999e+01 +20 9151 -8.821300e+02 -1.257200e+02 +9 9152 -1.954500e+02 3.286500e+02 +11 9152 4.439301e+02 2.642800e+02 +13 9152 -1.328850e+03 8.066700e+02 +20 9152 -3.299700e+02 -1.232800e+02 +9 9153 -1.230420e+03 3.307300e+02 +11 9153 -5.332500e+02 2.588500e+02 +14 9153 2.143100e+02 2.618800e+02 +9 9154 6.512900e+02 3.475500e+02 +13 9154 1.370830e+03 8.517300e+02 +18 9154 1.309301e+02 8.607007e+01 +9 9155 -1.420230e+03 3.603900e+02 +19 9155 1.153440e+03 3.293500e+02 +9 9156 -9.477700e+02 3.658800e+02 +11 9156 -2.660700e+02 2.923700e+02 +18 9156 -8.629600e+02 1.192700e+02 +9 9157 -9.477700e+02 3.658800e+02 +11 9157 -2.660700e+02 2.923700e+02 +18 9157 -8.629600e+02 1.192700e+02 +9 9158 -1.118660e+03 4.068900e+02 +11 9158 -4.273600e+02 3.320700e+02 +14 9158 2.553300e+02 2.970500e+02 +9 9159 5.824900e+02 4.409800e+02 +12 9159 -1.190000e+02 -3.373199e+02 +18 9159 9.423999e+01 1.434199e+02 +9 9160 -4.439800e+02 4.411599e+02 +12 9160 -9.614900e+02 -3.180500e+02 +18 9160 -5.480400e+02 1.605300e+02 +20 9160 -4.653101e+02 -6.064001e+01 +9 9161 -1.267910e+03 4.422100e+02 +11 9161 -5.688200e+02 3.644900e+02 +14 9161 2.030600e+02 3.064400e+02 +9 9162 -9.166200e+02 4.651300e+02 +11 9162 -2.336100e+02 3.880000e+02 +18 9162 -8.416600e+02 1.818101e+02 +9 9163 -9.408200e+02 4.696400e+02 +11 9163 -2.591000e+02 3.918000e+02 +14 9163 3.239300e+02 3.319400e+02 +18 9163 -8.573400e+02 1.847800e+02 +9 9164 -4.440601e+02 4.710100e+02 +11 9164 2.141899e+02 3.976100e+02 +18 9164 -5.475100e+02 1.786000e+02 +20 9164 -4.647400e+02 -4.500000e+01 +9 9165 -4.601600e+02 4.705601e+02 +11 9165 1.984000e+02 3.962700e+02 +18 9165 -5.579000e+02 1.784700e+02 +20 9165 -4.738300e+02 -4.554004e+01 +9 9166 -9.044700e+02 4.732100e+02 +11 9166 -2.245200e+02 3.946300e+02 +18 9166 -8.339800e+02 1.863101e+02 +9 9167 -4.215400e+02 4.831000e+02 +11 9167 2.351200e+02 4.095601e+02 +12 9167 -9.411200e+02 -2.875000e+02 +20 9167 -4.527200e+02 -3.931006e+01 +9 9168 -1.138950e+03 5.340801e+02 +11 9168 -4.514000e+02 4.511400e+02 +12 9168 -1.483580e+03 -2.312800e+02 +18 9168 -9.759000e+02 2.272600e+02 +20 9168 -8.368400e+02 -3.429993e+00 +9 9169 -9.197500e+02 5.654299e+02 +12 9169 -1.321430e+03 -2.118000e+02 +14 9169 3.374100e+02 3.709900e+02 +16 9169 1.106400e+02 5.336500e+02 +18 9169 -8.409800e+02 2.433800e+02 +9 9170 -1.484700e+03 5.681899e+02 +11 9170 -7.790100e+02 4.844600e+02 +14 9170 1.330700e+02 3.476300e+02 +9 9171 -1.166820e+03 6.145000e+02 +11 9171 -4.811400e+02 5.276600e+02 +14 9171 2.600700e+02 3.655400e+02 +20 9171 -8.485500e+02 4.026001e+01 +9 9172 -1.190510e+03 6.172000e+02 +14 9172 2.498800e+02 3.670900e+02 +19 9172 1.396720e+03 5.846000e+02 +9 9173 -1.248460e+03 6.416600e+02 +11 9173 -5.560300e+02 5.525100e+02 +14 9173 2.253000e+02 3.779700e+02 +9 9174 -7.831300e+02 -4.409000e+02 +18 9174 -9.280500e+02 -3.966600e+02 +20 9174 -7.675900e+02 -5.505000e+02 +9 9175 9.804099e+02 6.760010e+00 +10 9175 6.800500e+02 -5.368800e+02 +12 9175 1.689900e+02 -6.748300e+02 +18 9175 3.301801e+02 -1.277300e+02 +9 9176 9.938999e+02 2.502002e+01 +12 9176 1.798199e+02 -6.621000e+02 +18 9176 3.385699e+02 -1.171700e+02 +9 9177 8.589199e+02 7.322998e+01 +12 9177 6.301001e+01 -6.237900e+02 +9 9178 6.271201e+02 1.072300e+02 +12 9178 -1.159000e+02 -5.941400e+02 +9 9179 -4.092700e+02 1.646599e+02 +12 9179 -9.438900e+02 -5.372600e+02 +9 9180 -1.648000e+02 1.719500e+02 +11 9180 4.676300e+02 1.100700e+02 +18 9180 -3.721700e+02 -1.181006e+01 +20 9180 -3.146100e+02 -2.073900e+02 +9 9181 -1.012100e+02 1.730801e+02 +13 9181 -9.867200e+02 2.210200e+02 +18 9181 -3.279700e+02 -1.173999e+01 +20 9181 -2.773300e+02 -2.073800e+02 +9 9182 5.280701e+02 2.062900e+02 +13 9182 1.060800e+03 9.853701e+02 +9 9183 3.238700e+02 2.504399e+02 +17 9183 -2.204500e+02 8.497600e+02 +9 9184 3.079900e+02 2.511300e+02 +17 9184 -2.536801e+02 8.524200e+02 +9 9185 -1.484460e+03 3.131300e+02 +10 9185 -1.013430e+03 -3.231100e+02 +9 9186 -1.204140e+03 3.514600e+02 +11 9186 -5.079000e+02 2.787700e+02 +14 9186 2.235100e+02 2.713000e+02 +9 9187 -4.149000e+02 3.554399e+02 +11 9187 2.409500e+02 2.880700e+02 +18 9187 -5.313400e+02 1.071100e+02 +9 9188 -9.449600e+02 3.569600e+02 +11 9188 -2.628800e+02 2.844000e+02 +18 9188 -8.611800e+02 1.143800e+02 +9 9189 -9.366600e+02 3.643700e+02 +11 9189 -2.547300e+02 2.917800e+02 +18 9189 -8.554400e+02 1.195300e+02 +9 9190 1.030440e+03 3.704600e+02 +12 9190 2.431600e+02 -3.961899e+02 +18 9190 3.689900e+02 9.362000e+01 +20 9190 3.192400e+02 -1.124301e+02 +9 9191 1.055130e+03 3.778600e+02 +12 9191 2.612400e+02 -3.911000e+02 +9 9192 1.041290e+03 4.043500e+02 +12 9192 2.535699e+02 -3.707200e+02 +18 9192 3.774600e+02 1.151000e+02 +9 9193 1.057030e+03 4.188800e+02 +12 9193 2.635000e+02 -3.605000e+02 +9 9194 1.057030e+03 4.188800e+02 +12 9194 2.662400e+02 -3.592000e+02 +18 9194 3.859000e+02 1.229900e+02 +20 9194 3.332700e+02 -8.703003e+01 +9 9195 5.412600e+02 4.314900e+02 +12 9195 -1.494900e+02 -3.443600e+02 +17 9195 -1.017270e+03 8.181600e+02 +20 9195 6.466003e+01 -7.627002e+01 +9 9196 7.129700e+02 4.408500e+02 +12 9196 -1.856995e+01 -3.394900e+02 +13 9196 1.540460e+03 1.034420e+03 +18 9196 1.744700e+02 1.412100e+02 +9 9197 5.624099e+02 4.476400e+02 +12 9197 -1.329600e+02 -3.327500e+02 +17 9197 -9.797300e+02 8.468300e+02 +9 9198 -1.287590e+03 4.590000e+02 +11 9198 -5.878700e+02 3.805200e+02 +14 9198 1.969500e+02 3.127900e+02 +16 9198 -4.789001e+01 4.596300e+02 +9 9199 -1.518960e+03 5.078900e+02 +19 9199 1.087070e+03 4.511000e+02 +20 9199 -1.045420e+03 -1.178998e+01 +9 9200 -7.188900e+02 5.625000e+02 +11 9200 -5.314001e+01 4.817100e+02 +18 9200 -7.147700e+02 2.396100e+02 +20 9200 -6.094500e+02 7.030029e+00 +9 9201 -7.044400e+02 5.647200e+02 +11 9201 -3.871002e+01 4.835601e+02 +18 9201 -7.058800e+02 2.401699e+02 +20 9201 -6.017700e+02 7.849976e+00 +9 9202 -1.439480e+03 6.138900e+02 +11 9202 -7.382700e+02 5.285000e+02 +19 9202 1.152850e+03 5.559100e+02 +9 9203 -3.449000e+02 -5.354004e+01 +12 9203 -8.984500e+02 -7.123199e+02 +9 9204 -8.806995e+01 -2.500000e+01 +12 9204 -6.302400e+02 -6.932500e+02 +18 9204 -3.217600e+02 -1.356100e+02 +9 9205 -3.954000e+02 -1.818994e+01 +11 9205 2.573600e+02 -7.163000e+01 +18 9205 -5.251200e+02 -1.271700e+02 +9 9206 6.793401e+02 -1.420996e+01 +12 9206 -8.044995e+01 -6.917100e+02 +18 9206 1.442900e+02 -1.375000e+02 +9 9207 5.908799e+02 -1.072998e+01 +12 9207 -1.479200e+02 -6.881000e+02 +18 9207 9.043005e+01 -1.344301e+02 +9 9208 -2.479500e+02 -8.810059e+00 +11 9208 3.944700e+02 -6.367999e+01 +13 9208 -1.539130e+03 -2.339800e+02 +18 9208 -4.299301e+02 -1.232700e+02 +20 9208 -3.642600e+02 -3.046100e+02 +9 9209 -2.110900e+02 2.920044e+00 +11 9209 4.271801e+02 -5.260999e+01 +18 9209 -4.059500e+02 -1.161600e+02 +20 9209 -3.434399e+02 -2.985000e+02 +9 9210 6.616899e+02 6.790039e+00 +17 9210 -6.235699e+02 4.768994e+01 +9 9211 5.925500e+02 4.937000e+01 +12 9211 -1.459500e+02 -6.413800e+02 +18 9211 9.182996e+01 -9.792004e+01 +9 9212 4.230300e+02 7.497998e+01 +13 9212 6.473101e+02 4.971899e+02 +9 9213 -4.086500e+02 1.110601e+02 +12 9213 -9.461800e+02 -5.798900e+02 +9 9214 -1.062500e+02 2.269099e+02 +13 9214 -9.937400e+02 3.815901e+02 +18 9214 -3.297600e+02 2.163000e+01 +9 9215 -1.582400e+02 2.321699e+02 +11 9215 4.744100e+02 1.702200e+02 +13 9215 -1.199080e+03 4.774500e+02 +9 9216 -1.817500e+02 2.435701e+02 +13 9216 -1.281460e+03 5.368700e+02 +9 9217 -1.471801e+02 2.478600e+02 +11 9217 4.816200e+02 1.840300e+02 +13 9217 -1.151130e+03 5.074199e+02 +18 9217 -3.587600e+02 3.504004e+01 +20 9217 -3.033400e+02 -1.672700e+02 +9 9218 8.566201e+02 2.948600e+02 +12 9218 6.208997e+01 -4.529200e+02 +18 9218 2.562400e+02 5.031006e+01 +9 9219 -1.225280e+03 3.029399e+02 +11 9219 -5.281000e+02 2.321600e+02 +20 9219 -8.902600e+02 -1.267500e+02 +9 9220 -2.281200e+02 3.085100e+02 +12 9220 -7.758500e+02 -4.265100e+02 +18 9220 -4.124200e+02 7.458008e+01 +9 9221 -9.013600e+02 3.140100e+02 +11 9221 -2.220300e+02 2.438900e+02 +20 9221 -7.147100e+02 -1.242400e+02 +9 9222 4.156600e+02 3.640601e+02 +12 9222 -4.527400e+02 -3.921500e+02 +9 9223 -1.207100e+03 3.873301e+02 +11 9223 -5.108400e+02 3.123300e+02 +18 9223 -1.022580e+03 1.374299e+02 +19 9223 1.308620e+03 3.844000e+02 +20 9223 -8.780800e+02 -8.108997e+01 +9 9224 -1.166050e+03 4.025000e+02 +11 9224 -4.723000e+02 3.273000e+02 +18 9224 -9.972800e+02 1.465200e+02 +20 9224 -8.556400e+02 -7.337000e+01 +9 9225 -9.688700e+02 4.053900e+02 +11 9225 -2.854700e+02 3.309200e+02 +18 9225 -8.746400e+02 1.454900e+02 +9 9226 1.014180e+03 4.185100e+02 +12 9226 2.322800e+02 -3.599100e+02 +18 9226 3.600400e+02 1.230100e+02 +9 9227 -4.368700e+02 4.313700e+02 +11 9227 2.209600e+02 3.605900e+02 +12 9227 -9.560500e+02 -3.256801e+02 +9 9228 -4.368700e+02 4.313700e+02 +11 9228 2.209600e+02 3.605900e+02 +12 9228 -9.560500e+02 -3.256801e+02 +20 9228 -4.613300e+02 -6.531995e+01 +9 9229 -2.235699e+02 4.453800e+02 +16 9229 7.354700e+02 4.421600e+02 +9 9230 -8.638000e+02 4.489000e+02 +11 9230 -1.856600e+02 3.725100e+02 +20 9230 -6.914600e+02 -5.206995e+01 +9 9231 -1.841600e+02 4.569900e+02 +13 9231 -1.198440e+03 1.052400e+03 +9 9232 -8.685100e+02 4.631200e+02 +11 9232 -1.904200e+02 3.856600e+02 +20 9232 -6.937100e+02 -4.485999e+01 +9 9233 -9.475400e+02 4.809099e+02 +11 9233 -2.649900e+02 4.023201e+02 +18 9233 -8.606000e+02 1.920200e+02 +9 9234 -3.844700e+02 4.846100e+02 +12 9234 -9.099200e+02 -2.855300e+02 +20 9234 -4.322400e+02 -3.803003e+01 +9 9235 -1.429450e+03 4.876000e+02 +16 9235 -1.037200e+02 4.683800e+02 +19 9235 1.145600e+03 4.461400e+02 +9 9236 -3.618700e+02 5.208201e+02 +12 9236 -8.861600e+02 -2.583199e+02 +9 9237 -1.335800e+03 5.798301e+02 +11 9237 -6.364800e+02 4.952000e+02 +19 9237 1.232680e+03 5.414800e+02 +9 9238 -1.335800e+03 5.798301e+02 +11 9238 -6.364800e+02 4.952000e+02 +19 9238 1.232680e+03 5.414800e+02 +9 9239 -4.005300e+02 -8.800049e-01 +12 9239 -9.440300e+02 -6.696600e+02 +9 9240 -2.492700e+02 9.770020e+00 +11 9240 3.929200e+02 -4.550000e+01 +13 9240 -1.542610e+03 -1.725699e+02 +18 9240 -4.303500e+02 -1.117000e+02 +20 9240 -3.649000e+02 -2.943400e+02 +9 9241 5.872800e+02 3.455005e+01 +12 9241 -1.504900e+02 -6.529600e+02 +9 9242 -4.424700e+02 1.101300e+02 +12 9242 -9.738900e+02 -5.800000e+02 +9 9243 6.615100e+02 1.148800e+02 +12 9243 -9.169995e+01 -5.897100e+02 +9 9244 3.789000e+02 1.241200e+02 +13 9244 4.862700e+02 6.862100e+02 +9 9245 -1.509900e+02 1.327600e+02 +13 9245 -1.174960e+03 1.519500e+02 +18 9245 -3.634600e+02 -3.593005e+01 +20 9245 -3.072600e+02 -2.284399e+02 +9 9246 7.943000e+02 1.468800e+02 +12 9246 -1.881700e+02 -5.676000e+02 +18 9246 2.161300e+02 -3.991003e+01 +9 9247 -1.244700e+02 1.681400e+02 +13 9247 -1.070910e+03 2.277400e+02 +18 9247 -3.437500e+02 -1.516003e+01 +20 9247 -2.906899e+02 -2.106500e+02 +9 9248 7.785400e+02 1.777500e+02 +12 9248 1.390015e+00 -5.422200e+02 +9 9249 7.262300e+02 2.099199e+02 +13 9249 1.599280e+03 3.981300e+02 +9 9250 -2.380800e+02 2.551500e+02 +11 9250 4.031000e+02 1.909100e+02 +20 9250 -3.549100e+02 -1.623800e+02 +9 9251 5.113700e+02 2.571500e+02 +16 9251 5.368800e+02 4.761400e+02 +9 9252 -1.178740e+03 3.984800e+02 +11 9252 -4.844000e+02 3.237300e+02 +19 9252 1.331750e+03 3.995701e+02 +9 9253 5.758101e+02 4.012200e+02 +12 9253 -1.243400e+02 -3.681200e+02 +9 9254 5.993301e+02 4.023000e+02 +12 9254 -1.075000e+02 -3.684600e+02 +9 9255 5.835400e+02 4.049600e+02 +12 9255 -1.175300e+02 -3.645601e+02 +18 9255 9.571997e+01 1.220901e+02 +20 9255 8.706006e+01 -8.938000e+01 +9 9256 1.081500e+03 4.088401e+02 +12 9256 2.814600e+02 -3.683800e+02 +18 9256 4.002100e+02 1.160901e+02 +9 9257 1.068350e+03 4.129500e+02 +12 9257 2.716899e+02 -3.652200e+02 +18 9257 3.920200e+02 1.183900e+02 +9 9258 -1.061210e+03 4.143900e+02 +11 9258 -3.730300e+02 3.376500e+02 +18 9258 -9.319300e+02 1.514600e+02 +9 9259 -8.720500e+02 4.254399e+02 +11 9259 -1.935300e+02 3.498201e+02 +20 9259 -6.963100e+02 -6.492004e+01 +9 9260 -1.186590e+03 4.321500e+02 +11 9260 -4.913700e+02 3.548900e+02 +18 9260 -1.008960e+03 1.648201e+02 +9 9261 5.504299e+02 4.629800e+02 +12 9261 -1.424500e+02 -3.199800e+02 +9 9262 -1.302220e+03 4.628800e+02 +11 9262 -6.023900e+02 3.839800e+02 +19 9262 1.232840e+03 4.431799e+02 +9 9263 7.269800e+02 4.948800e+02 +12 9263 -5.589966e+00 -2.984800e+02 +9 9264 5.922000e+02 5.082400e+02 +12 9264 -1.094500e+02 -2.859100e+02 +18 9264 1.012500e+02 1.849299e+02 +9 9265 -7.330900e+02 5.661500e+02 +12 9265 -1.169930e+03 -2.156500e+02 +9 9266 -8.860600e+02 5.748201e+02 +12 9266 -1.295020e+03 -2.052300e+02 +9 9267 -5.309500e+02 -4.237600e+02 +11 9267 2.776300e+02 -4.574200e+02 +9 9268 -3.470500e+02 -5.796997e+01 +12 9268 -9.003600e+02 -7.164100e+02 +9 9269 -2.645000e+02 -1.160999e+01 +13 9269 -1.600910e+03 -2.352100e+02 +9 9270 6.550601e+02 -4.339966e+00 +17 9270 -6.366899e+02 2.789001e+01 +18 9270 1.293400e+02 -1.311700e+02 +9 9271 9.032500e+02 3.985999e+01 +12 9271 9.655005e+01 -6.504200e+02 +9 9272 4.635200e+02 5.356006e+01 +13 9272 8.049500e+02 4.097800e+02 +9 9273 3.733700e+02 1.081100e+02 +13 9273 4.643401e+02 6.274800e+02 +9 9274 3.733700e+02 1.081100e+02 +13 9274 4.643401e+02 6.274800e+02 +9 9275 -2.033000e+02 1.082000e+02 +12 9275 -7.571000e+02 -5.837400e+02 +13 9275 -1.368600e+03 1.208600e+02 +9 9276 -1.240601e+02 1.097000e+02 +13 9276 -1.072510e+03 4.373999e+01 +18 9276 -3.444600e+02 -5.165002e+01 +9 9277 -3.616600e+02 1.107100e+02 +11 9277 2.898000e+02 5.248999e+01 +12 9277 -9.067400e+02 -5.806200e+02 +9 9278 3.743800e+02 1.170100e+02 +13 9278 4.676599e+02 6.591799e+02 +9 9279 8.180701e+02 1.184200e+02 +12 9279 3.115002e+01 -5.890100e+02 +9 9280 7.702000e+02 1.222100e+02 +17 9280 -4.434600e+02 2.617400e+02 +9 9281 7.531299e+02 1.221000e+02 +13 9281 1.680460e+03 1.168000e+02 +9 9282 7.655601e+02 1.283201e+02 +12 9282 -9.550049e+00 -5.804900e+02 +9 9283 8.162800e+02 1.406500e+02 +12 9283 2.997998e+01 -5.714200e+02 +9 9284 7.114600e+02 1.600200e+02 +12 9284 -1.297100e+02 -5.559100e+02 +9 9285 6.458999e+02 2.060100e+02 +17 9285 -6.530699e+02 4.299099e+02 +9 9286 6.607500e+02 2.125300e+02 +13 9286 1.397290e+03 4.241799e+02 +9 9287 6.501101e+02 2.132800e+02 +13 9287 1.360860e+03 4.258301e+02 +17 9287 -6.470601e+02 4.432100e+02 +9 9288 9.099600e+02 2.228201e+02 +12 9288 1.019301e+02 -5.077900e+02 +9 9289 6.617200e+02 2.335300e+02 +13 9289 1.400060e+03 4.891200e+02 +9 9290 7.213899e+02 2.638500e+02 +13 9290 1.587800e+03 5.711000e+02 +9 9291 6.987200e+02 2.641400e+02 +13 9291 1.515900e+03 5.724000e+02 +9 9292 7.357100e+02 2.665000e+02 +13 9292 1.632500e+03 5.776799e+02 +17 9292 -5.075000e+02 5.344500e+02 +9 9293 7.357100e+02 2.665000e+02 +13 9293 1.632500e+03 5.776799e+02 +17 9293 -5.075000e+02 5.344500e+02 +9 9294 6.987400e+02 2.699000e+02 +12 9294 -5.912000e+01 -4.706500e+02 +13 9294 1.516480e+03 5.909099e+02 +9 9295 7.069299e+02 2.716599e+02 +13 9295 1.542470e+03 5.960801e+02 +9 9296 7.069299e+02 2.716599e+02 +13 9296 1.542470e+03 5.960801e+02 +9 9297 7.154800e+02 2.742500e+02 +12 9297 -4.633997e+01 -4.670800e+02 +9 9298 7.154800e+02 2.742500e+02 +12 9298 -4.633997e+01 -4.670800e+02 +17 9298 -5.443101e+02 5.503401e+02 +9 9299 7.099299e+02 2.738800e+02 +13 9299 1.551230e+03 6.024000e+02 +9 9300 6.983201e+02 2.737200e+02 +13 9300 1.516150e+03 6.035901e+02 +9 9301 7.737700e+02 2.921799e+02 +17 9301 -4.411899e+02 5.790400e+02 +9 9302 8.603701e+02 2.934299e+02 +12 9302 6.501001e+01 -4.541000e+02 +9 9303 8.530901e+02 2.941400e+02 +12 9303 -1.229980e+00 -4.540000e+02 +9 9304 7.176599e+02 2.943201e+02 +13 9304 1.575090e+03 6.654100e+02 +17 9304 -5.439900e+02 5.873500e+02 +18 9304 1.719200e+02 5.189001e+01 +9 9305 6.626599e+02 3.285701e+02 +13 9305 1.408430e+03 7.935800e+02 +9 9306 6.563101e+02 3.283000e+02 +13 9306 1.387040e+03 7.922500e+02 +17 9306 -6.341700e+02 6.635601e+02 +9 9307 8.911699e+02 3.358900e+02 +12 9307 1.055200e+02 -4.210800e+02 +18 9307 2.812700e+02 7.563000e+01 +20 9307 2.459399e+02 -1.285900e+02 +9 9308 -9.315300e+02 3.445500e+02 +11 9308 -2.505500e+02 2.724300e+02 +18 9308 -8.525000e+02 1.065901e+02 +9 9309 -2.921400e+02 3.452400e+02 +11 9309 3.556400e+02 2.784800e+02 +13 9309 -1.659740e+03 9.265300e+02 +9 9310 3.747200e+02 3.955901e+02 +16 9310 4.277200e+02 5.722000e+02 +9 9311 -2.860699e+02 3.999900e+02 +13 9311 -1.636110e+03 1.103600e+03 +9 9312 -3.110300e+02 4.082200e+02 +12 9312 -8.508900e+02 -3.465800e+02 +9 9313 1.061250e+03 4.147800e+02 +12 9313 2.669200e+02 -3.636899e+02 +9 9314 7.666101e+02 4.434900e+02 +13 9314 1.704380e+03 1.038650e+03 +17 9314 -6.089399e+02 8.188800e+02 +9 9315 6.243301e+02 4.458101e+02 +13 9315 1.268740e+03 1.057870e+03 +17 9315 -8.670700e+02 8.369700e+02 +9 9316 8.544500e+02 4.875500e+02 +12 9316 8.832996e+01 -3.057400e+02 +9 9317 6.700901e+02 4.930200e+02 +12 9317 -5.031006e+01 -2.988700e+02 +17 9317 -7.835500e+02 9.198899e+02 +9 9318 6.607800e+02 5.138301e+02 +12 9318 -5.687000e+01 -2.829100e+02 +18 9318 1.431000e+02 1.872000e+02 +20 9318 1.266200e+02 -3.406995e+01 +9 9319 8.888601e+02 5.525901e+02 +12 9319 1.734200e+02 -2.576600e+02 +9 9320 8.888601e+02 5.525901e+02 +12 9320 1.734200e+02 -2.576600e+02 +9 9321 3.286600e+02 -5.896997e+01 +13 9321 2.799301e+02 -2.579956e+00 +9 9322 -2.592300e+02 7.670044e+00 +13 9322 -1.575590e+03 -1.786200e+02 +9 9323 -2.579800e+02 1.031995e+01 +13 9323 -1.571900e+03 -1.703000e+02 +9 9324 5.963401e+02 1.241801e+02 +17 9324 -7.470400e+02 2.749700e+02 +9 9325 9.112100e+02 1.259500e+02 +12 9325 1.033800e+02 -5.842500e+02 +18 9325 2.892400e+02 -5.637000e+01 +9 9326 7.297800e+02 1.523201e+02 +13 9326 1.609140e+03 2.141100e+02 +9 9327 5.574700e+02 1.525100e+02 +17 9327 -8.209800e+02 3.301599e+02 +9 9328 -2.370699e+02 1.601500e+02 +11 9328 4.043900e+02 9.945001e+01 +13 9328 -1.486650e+03 3.049099e+02 +9 9329 -9.877002e+01 2.004399e+02 +13 9329 -9.715700e+02 3.028600e+02 +9 9330 6.277800e+02 2.389000e+02 +13 9330 1.293650e+03 5.095801e+02 +9 9331 -1.470699e+02 2.526799e+02 +13 9331 -1.149730e+03 5.251100e+02 +9 9332 7.761299e+02 2.562400e+02 +12 9332 -1.099854e-01 -4.815699e+02 +9 9333 7.440300e+02 2.642400e+02 +13 9333 1.658230e+03 5.704600e+02 +9 9334 7.385200e+02 2.650400e+02 +17 9334 -5.022600e+02 5.331400e+02 +9 9335 7.384299e+02 2.701500e+02 +13 9335 1.641760e+03 5.899600e+02 +17 9335 -5.023500e+02 5.416000e+02 +9 9336 7.384299e+02 2.701500e+02 +13 9336 1.641760e+03 5.899600e+02 +17 9336 -5.023500e+02 5.416000e+02 +9 9337 7.184199e+02 2.721599e+02 +13 9337 1.578610e+03 5.964800e+02 +9 9338 7.184199e+02 2.721599e+02 +12 9338 -4.393994e+01 -4.690500e+02 +13 9338 1.578610e+03 5.964800e+02 +9 9339 7.411499e+02 2.724500e+02 +13 9339 1.650140e+03 5.941500e+02 +9 9340 7.383000e+02 2.742600e+02 +13 9340 1.641460e+03 6.024900e+02 +17 9340 -5.023900e+02 5.495901e+02 +9 9341 7.383000e+02 2.742600e+02 +13 9341 1.641460e+03 6.024900e+02 +9 9342 7.327500e+02 2.744900e+02 +13 9342 1.623380e+03 6.031400e+02 +17 9342 -5.127500e+02 5.501799e+02 +9 9343 7.356799e+02 2.755200e+02 +13 9343 1.632480e+03 6.049600e+02 +17 9343 -5.077100e+02 5.513700e+02 +9 9344 7.185801e+02 2.775701e+02 +13 9344 1.579160e+03 6.129000e+02 +9 9345 7.521299e+02 2.793900e+02 +17 9345 -4.755200e+02 5.576200e+02 +9 9346 -2.933199e+02 2.817600e+02 +11 9346 3.544200e+02 2.166100e+02 +13 9346 -1.674660e+03 7.241799e+02 +9 9347 -1.107100e+02 2.821100e+02 +11 9347 5.033400e+02 2.156800e+02 +13 9347 -9.888100e+02 5.248500e+02 +9 9348 -2.931000e+02 2.841500e+02 +13 9348 -1.669520e+03 7.313500e+02 +9 9349 -3.040900e+02 2.851599e+02 +13 9349 -1.709560e+03 7.417200e+02 +9 9350 -1.993500e+02 2.977300e+02 +13 9350 -1.338030e+03 7.227400e+02 +9 9351 -1.869301e+02 2.983201e+02 +13 9351 -1.292220e+03 7.077800e+02 +9 9352 7.317400e+02 2.992700e+02 +13 9352 1.620660e+03 6.791600e+02 +9 9353 6.325200e+02 3.043301e+02 +13 9353 1.309130e+03 7.157300e+02 +9 9354 -2.533600e+02 3.047600e+02 +13 9354 -1.527700e+03 7.736500e+02 +9 9355 6.216499e+02 4.475300e+02 +13 9355 1.261940e+03 1.062300e+03 +9 9356 7.100100e+02 4.614199e+02 +13 9356 1.532610e+03 1.098590e+03 +9 9357 -2.242400e+02 4.667700e+02 +13 9357 -1.261630e+03 9.698201e+02 +9 9358 6.155801e+02 4.672900e+02 +13 9358 1.241000e+03 1.123830e+03 +9 9359 7.101299e+02 4.685200e+02 +13 9359 1.532510e+03 1.119940e+03 +9 9360 6.621499e+02 4.921500e+02 +17 9360 -7.972100e+02 9.200701e+02 +9 9361 6.643201e+02 4.947100e+02 +17 9361 -7.931800e+02 9.245500e+02 +10 9362 1.522830e+03 -1.501801e+02 +12 9362 9.413401e+02 -3.309800e+02 +18 9362 1.019110e+03 1.376699e+02 +10 9363 1.261950e+03 -3.916000e+02 +18 9363 7.904299e+02 -4.819995e+01 +20 9363 6.818401e+02 -2.315000e+02 +10 9364 1.261950e+03 -3.916000e+02 +18 9364 7.904299e+02 -4.819995e+01 +10 9365 1.238240e+03 -2.529600e+02 +12 9365 6.638201e+02 -4.254600e+02 +18 9365 7.802000e+02 6.489001e+01 +20 9365 6.701399e+02 -1.337500e+02 +10 9366 1.462160e+03 -7.375000e+01 +12 9366 8.793201e+02 -2.508101e+02 +20 9366 8.197600e+02 -1.223999e+01 +10 9367 1.315550e+03 -4.372700e+02 +18 9367 8.299600e+02 -8.622998e+01 +20 9367 7.170000e+02 -2.639700e+02 +10 9368 1.618780e+03 -4.188300e+02 +12 9368 1.015190e+03 -6.064399e+02 +10 9369 1.350820e+03 -3.845400e+02 +18 9369 8.624600e+02 -4.854004e+01 +20 9369 7.453000e+02 -2.317200e+02 +10 9370 1.433150e+03 -3.803300e+02 +20 9370 7.993701e+02 -2.309900e+02 +10 9371 1.610140e+03 -3.357500e+02 +12 9371 1.012720e+03 -5.247300e+02 +10 9372 1.192790e+03 -3.109900e+02 +12 9372 6.181699e+02 -4.824399e+02 +17 9372 1.536900e+03 5.853401e+02 +18 9372 7.403501e+02 2.112000e+01 +20 9372 6.389299e+02 -1.730000e+02 +10 9373 1.107160e+03 -3.156700e+02 +12 9373 5.332300e+02 -4.857600e+02 +17 9373 1.283860e+03 5.594500e+02 +18 9373 6.645901e+02 2.176001e+01 +20 9373 5.812100e+02 -1.753700e+02 +10 9374 1.265170e+03 -3.013600e+02 +18 9374 8.002400e+02 2.567004e+01 +20 9374 6.899800e+02 -1.691899e+02 +10 9375 1.265170e+03 -3.013600e+02 +12 9375 6.883799e+02 -4.744800e+02 +18 9375 8.002400e+02 2.567004e+01 +20 9375 6.899800e+02 -1.691899e+02 +10 9376 1.342010e+03 -2.961100e+02 +12 9376 7.616201e+02 -4.721500e+02 +18 9376 8.614900e+02 2.645996e+01 +20 9376 7.410000e+02 -1.666801e+02 +10 9377 1.420520e+03 -2.900200e+02 +18 9377 9.233501e+02 2.716003e+01 +20 9377 7.941201e+02 -1.654399e+02 +10 9378 1.599490e+03 -2.456100e+02 +12 9378 1.007010e+03 -4.302000e+02 +18 9378 1.068060e+03 5.608008e+01 +10 9379 1.066090e+03 -1.656000e+02 +12 9379 5.128199e+02 -3.246500e+02 +18 9379 6.506201e+02 1.527400e+02 +20 9379 5.617800e+02 -5.763000e+01 +10 9380 1.691850e+03 -8.337000e+01 +12 9380 1.100600e+03 -2.710601e+02 +18 9380 1.152970e+03 1.847800e+02 +10 9381 1.152570e+03 -3.519000e+02 +12 9381 5.745601e+02 -5.260400e+02 +17 9381 1.384500e+03 4.680901e+02 +20 9381 6.087200e+02 -1.970900e+02 +10 9382 1.152570e+03 -3.519000e+02 +12 9382 5.745601e+02 -5.260400e+02 +18 9382 7.042300e+02 -1.367004e+01 +20 9382 6.087200e+02 -1.970900e+02 +10 9383 1.307700e+03 -3.424800e+02 +18 9383 8.304299e+02 -1.043005e+01 +20 9383 7.154900e+02 -1.984399e+02 +10 9384 1.466240e+03 -3.326600e+02 +18 9384 9.569099e+02 -1.402002e+01 +20 9384 8.225901e+02 -1.997700e+02 +10 9385 1.466240e+03 -3.326600e+02 +18 9385 9.569099e+02 -1.402002e+01 +20 9385 8.225901e+02 -1.997700e+02 +10 9386 1.386250e+03 -3.385100e+02 +18 9386 8.932800e+02 -1.116003e+01 +20 9386 7.688501e+02 -1.990500e+02 +10 9387 1.062550e+03 -2.682400e+02 +12 9387 4.908900e+02 -4.331801e+02 +17 9387 1.174150e+03 6.891899e+02 +18 9387 6.399600e+02 6.129004e+01 +20 9387 5.501201e+02 -1.387500e+02 +10 9388 1.300340e+03 -2.564301e+02 +12 9388 7.238101e+02 -4.322400e+02 +18 9388 8.308201e+02 5.803003e+01 +20 9388 7.139900e+02 -1.391300e+02 +10 9389 1.654380e+03 -2.512700e+02 +12 9389 1.059020e+03 -4.402100e+02 +18 9389 1.111780e+03 4.709998e+01 +20 9389 9.506001e+02 -1.468700e+02 +10 9390 1.455990e+03 -2.466000e+02 +12 9390 8.744500e+02 -4.280400e+02 +18 9390 9.570901e+02 6.293994e+01 +20 9390 8.205200e+02 -1.357400e+02 +10 9391 1.455990e+03 -2.466000e+02 +20 9391 8.205200e+02 -1.357400e+02 +10 9392 1.375120e+03 -2.505601e+02 +12 9392 7.999399e+02 -4.299100e+02 +18 9392 8.925400e+02 5.818994e+01 +20 9392 7.663799e+02 -1.375900e+02 +10 9393 1.549750e+03 -1.899900e+02 +12 9393 9.653201e+02 -3.754800e+02 +20 9393 8.858999e+02 -1.044301e+02 +10 9394 1.591500e+03 -1.682900e+02 +12 9394 1.005030e+03 -3.598199e+02 +18 9394 1.069440e+03 1.123700e+02 +20 9394 9.137500e+02 -9.289001e+01 +10 9395 1.591500e+03 -1.682900e+02 +12 9395 1.005030e+03 -3.598199e+02 +18 9395 1.069440e+03 1.123700e+02 +20 9395 9.137500e+02 -9.289001e+01 +10 9396 1.291490e+03 -1.689600e+02 +12 9396 7.205500e+02 -3.356300e+02 +20 9396 7.130500e+02 -7.390002e+01 +10 9397 1.248760e+03 -1.615699e+02 +12 9397 6.787300e+02 -3.335500e+02 +20 9397 6.831499e+02 -7.191003e+01 +10 9398 1.248760e+03 -1.615699e+02 +12 9398 6.787300e+02 -3.335500e+02 +18 9398 7.956001e+02 1.415601e+02 +20 9398 6.831499e+02 -7.191003e+01 +10 9399 1.450850e+03 -1.558400e+02 +12 9399 8.700601e+02 -3.290000e+02 +20 9399 8.205701e+02 -7.062000e+01 +10 9400 1.327970e+03 -1.438199e+02 +12 9400 7.563799e+02 -3.140200e+02 +20 9400 7.379399e+02 -5.950000e+01 +10 9401 1.489630e+03 -1.372400e+02 +12 9401 9.115300e+02 -3.175800e+02 +10 9402 1.489630e+03 -1.372400e+02 +12 9402 9.115300e+02 -3.175800e+02 +18 9402 9.911799e+02 1.505801e+02 +10 9403 1.405750e+03 -1.384500e+02 +12 9403 8.315801e+02 -3.129301e+02 +20 9403 7.912400e+02 -5.893994e+01 +10 9404 1.405750e+03 -1.384500e+02 +12 9404 8.315801e+02 -3.129301e+02 +18 9404 9.230901e+02 1.484600e+02 +20 9404 7.912400e+02 -5.893994e+01 +10 9405 1.386240e+03 -4.173700e+02 +18 9405 8.935400e+02 -8.127002e+01 +20 9405 7.706499e+02 -2.648500e+02 +10 9406 1.026340e+03 -3.995300e+02 +17 9406 1.043510e+03 3.540400e+02 +10 9407 1.119030e+03 -3.943600e+02 +12 9407 5.408199e+02 -5.665000e+02 +17 9407 1.292980e+03 3.618401e+02 +18 9407 6.728101e+02 -4.759998e+01 +20 9407 5.833799e+02 -2.302500e+02 +10 9408 1.468340e+03 -3.777800e+02 +18 9408 9.560801e+02 -4.712000e+01 +20 9408 8.221101e+02 -2.291300e+02 +10 9409 1.468340e+03 -3.777800e+02 +18 9409 9.560801e+02 -4.712000e+01 +20 9409 8.221101e+02 -2.291300e+02 +10 9410 1.084360e+03 -3.078101e+02 +12 9410 5.062200e+02 -4.731801e+02 +17 9410 1.214680e+03 5.875901e+02 +10 9411 1.308210e+03 -2.970400e+02 +18 9411 8.336299e+02 2.698999e+01 +20 9411 7.173201e+02 -1.666000e+02 +10 9412 1.381460e+03 -2.923101e+02 +18 9412 8.931201e+02 2.730005e+01 +20 9412 7.676399e+02 -1.657700e+02 +10 9413 1.459410e+03 -2.872000e+02 +12 9413 8.744199e+02 -4.692000e+02 +18 9413 9.549399e+02 2.720996e+01 +20 9413 8.200500e+02 -1.648500e+02 +10 9414 9.849099e+02 -2.761899e+02 +12 9414 4.181100e+02 -4.395200e+02 +17 9414 9.572400e+02 6.753201e+02 +20 9414 4.971300e+02 -1.416899e+02 +10 9415 1.145590e+03 -2.666100e+02 +12 9415 5.728201e+02 -4.372000e+02 +17 9415 1.387850e+03 6.878600e+02 +18 9415 7.036899e+02 5.658008e+01 +20 9415 6.065701e+02 -1.409700e+02 +10 9416 1.553000e+03 -2.574100e+02 +12 9416 9.643201e+02 -4.413300e+02 +18 9416 1.032010e+03 4.987000e+01 +10 9417 1.109900e+03 -2.450900e+02 +17 9417 1.299530e+03 7.352800e+02 +18 9417 6.740701e+02 8.225000e+01 +20 9417 5.819900e+02 -1.228500e+02 +10 9418 1.413890e+03 -2.227000e+02 +12 9418 8.343101e+02 -4.027300e+02 +18 9418 9.238999e+02 8.103003e+01 +20 9418 7.928201e+02 -1.198199e+02 +10 9419 1.143070e+03 -1.657600e+02 +12 9419 5.793601e+02 -3.269100e+02 +18 9419 7.091201e+02 1.430801e+02 +10 9420 -1.594000e+03 -1.097100e+02 +15 9420 5.249000e+02 3.482600e+02 +16 9420 -6.783700e+02 5.009299e+02 +10 9421 1.584020e+03 -9.718005e+01 +12 9421 1.001810e+03 -2.798800e+02 +18 9421 1.070430e+03 1.816799e+02 +10 9422 1.030850e+03 -5.043199e+02 +18 9422 5.980801e+02 -1.258000e+02 +20 9422 5.204000e+02 -3.029600e+02 +10 9423 1.030850e+03 -5.043199e+02 +12 9423 4.519700e+02 -6.815900e+02 +10 9424 1.279220e+03 -4.484200e+02 +20 9424 6.920200e+02 -2.730300e+02 +10 9425 1.126180e+03 -4.346300e+02 +12 9425 5.469399e+02 -6.056899e+02 +17 9425 1.296660e+03 2.620601e+02 +18 9425 6.777500e+02 -7.720996e+01 +20 9425 5.864099e+02 -2.573101e+02 +10 9426 1.192350e+03 -4.309800e+02 +12 9426 6.131499e+02 -6.117900e+02 +17 9426 1.473480e+03 2.553600e+02 +18 9426 7.325901e+02 -7.982996e+01 +20 9426 6.330801e+02 -2.548199e+02 +10 9427 5.261899e+02 -4.050100e+02 +12 9427 -1.291003e+01 -5.319700e+02 +18 9427 1.980500e+02 -1.071997e+01 +10 9428 1.270230e+03 -3.451400e+02 +12 9428 6.860601e+02 -5.199500e+02 +20 9428 6.883401e+02 -1.991000e+02 +10 9429 1.019920e+03 -3.424600e+02 +12 9429 4.489200e+02 -5.070200e+02 +17 9429 1.039400e+03 5.054700e+02 +18 9429 5.975500e+02 3.920044e+00 +20 9429 5.184500e+02 -1.883300e+02 +10 9430 1.425080e+03 -3.357500e+02 +18 9430 9.241399e+02 -1.217004e+01 +20 9430 7.948899e+02 -1.991100e+02 +10 9431 1.013800e+03 -2.636100e+02 +12 9431 4.458500e+02 -4.276899e+02 +17 9431 1.036500e+03 7.238600e+02 +20 9431 5.174600e+02 -1.343400e+02 +10 9432 1.013800e+03 -2.636100e+02 +12 9432 4.458500e+02 -4.276899e+02 +17 9432 1.036500e+03 7.238600e+02 +10 9433 1.575420e+03 -2.281700e+02 +12 9433 9.897700e+02 -4.196801e+02 +18 9433 1.054730e+03 6.556006e+01 +20 9433 9.022700e+02 -1.320800e+02 +10 9434 5.371499e+02 -2.221100e+02 +18 9434 2.175000e+02 1.630400e+02 +10 9435 1.056460e+03 -2.066801e+02 +12 9435 4.891700e+02 -3.679301e+02 +10 9436 1.056460e+03 -2.066801e+02 +12 9436 4.891700e+02 -3.679301e+02 +17 9436 1.168480e+03 8.488700e+02 +18 9436 6.368401e+02 1.139000e+02 +20 9436 5.486699e+02 -9.434998e+01 +10 9437 1.408320e+03 -1.639399e+02 +12 9437 8.328101e+02 -3.406400e+02 +10 9438 1.496850e+03 -9.385999e+01 +12 9438 9.206599e+02 -2.751899e+02 +18 9438 1.000940e+03 1.847800e+02 +20 9438 8.576299e+02 -3.369995e+01 +10 9439 1.496850e+03 -9.385999e+01 +12 9439 9.206599e+02 -2.751899e+02 +18 9439 1.000940e+03 1.847800e+02 +20 9439 8.576299e+02 -3.369995e+01 +10 9440 2.229800e+02 9.023000e+02 +12 9440 -4.278101e+02 6.678300e+02 +18 9440 -3.112000e+01 9.788101e+02 +20 9440 -2.084998e+01 6.263400e+02 +10 9441 9.941201e+02 -5.151300e+02 +12 9441 4.168000e+02 -6.847800e+02 +17 9441 9.460300e+02 6.523999e+01 +18 9441 5.673899e+02 -1.388800e+02 +20 9441 4.945601e+02 -3.109301e+02 +10 9442 9.724800e+02 -5.025800e+02 +20 9442 4.817700e+02 -2.996600e+02 +10 9443 9.724800e+02 -5.025800e+02 +17 9443 8.822500e+02 9.832996e+01 +20 9443 4.817700e+02 -2.996600e+02 +10 9444 9.680500e+02 -4.783800e+02 +17 9444 8.707100e+02 1.611799e+02 +20 9444 4.794500e+02 -2.837100e+02 +10 9445 6.075300e+02 -4.563700e+02 +12 9445 7.393005e+01 -5.928600e+02 +20 9445 2.338101e+02 -2.455100e+02 +10 9446 1.437640e+03 -4.462200e+02 +18 9446 9.251799e+02 -1.041100e+02 +20 9446 7.972500e+02 -2.744500e+02 +10 9447 1.157470e+03 -3.892400e+02 +12 9447 5.746499e+02 -5.689301e+02 +18 9447 7.024299e+02 -4.777002e+01 +20 9447 6.083401e+02 -2.315300e+02 +10 9448 1.157470e+03 -3.892400e+02 +12 9448 5.746499e+02 -5.689301e+02 +17 9448 1.380040e+03 3.520901e+02 +18 9448 7.024299e+02 -4.777002e+01 +20 9448 6.083401e+02 -2.315300e+02 +10 9449 1.060420e+03 -3.657300e+02 +12 9449 4.847500e+02 -5.333900e+02 +17 9449 1.150060e+03 4.375400e+02 +18 9449 6.293101e+02 -1.931995e+01 +20 9449 5.455200e+02 -2.077100e+02 +10 9450 1.060420e+03 -3.657300e+02 +12 9450 4.847500e+02 -5.333900e+02 +17 9450 1.150060e+03 4.375400e+02 +18 9450 6.293101e+02 -1.931995e+01 +20 9450 5.455200e+02 -2.077100e+02 +10 9451 8.637900e+02 -3.433700e+02 +18 9451 5.058600e+02 3.959998e+01 +10 9452 1.182750e+03 -2.594500e+02 +12 9452 6.110000e+02 -4.296500e+02 +17 9452 1.482050e+03 6.945900e+02 +18 9452 7.337100e+02 5.827002e+01 +10 9453 1.203870e+03 -2.442600e+02 +12 9453 6.311499e+02 -4.144900e+02 +17 9453 1.542960e+03 7.382200e+02 +18 9453 7.534199e+02 7.646997e+01 +20 9453 6.503201e+02 -1.269700e+02 +10 9454 1.135460e+03 -2.454800e+02 +12 9454 5.636499e+02 -4.121400e+02 +18 9454 6.972000e+02 7.823999e+01 +20 9454 6.017700e+02 -1.241500e+02 +10 9455 1.075260e+03 -2.355400e+02 +12 9455 5.060500e+02 -4.000601e+02 +17 9455 1.212340e+03 7.746400e+02 +18 9455 6.493899e+02 8.859009e+01 +20 9455 5.595400e+02 -1.150699e+02 +10 9456 1.591280e+03 -1.307400e+02 +12 9456 1.007590e+03 -3.167000e+02 +18 9456 1.074340e+03 1.484700e+02 +20 9456 9.154500e+02 -6.104004e+01 +10 9457 -1.406000e+03 -1.302800e+02 +14 9457 -1.515800e+02 3.909800e+02 +10 9458 1.323860e+03 -9.297998e+01 +18 9458 8.639700e+02 1.918700e+02 +10 9459 1.400140e+03 -8.843994e+01 +12 9459 8.327700e+02 -2.632200e+02 +10 9460 1.361030e+03 -8.930005e+01 +18 9460 8.959500e+02 1.964700e+02 +10 9461 1.516320e+03 -7.765002e+01 +12 9461 9.403601e+02 -2.604500e+02 +18 9461 1.018320e+03 1.970901e+02 +10 9462 -1.606610e+03 -1.159998e+01 +16 9462 -6.960800e+02 5.709299e+02 +10 9463 1.671600e+02 9.169299e+02 +12 9463 -4.752400e+02 6.791799e+02 +10 9464 1.067960e+03 -5.148900e+02 +12 9464 4.856500e+02 -6.882000e+02 +20 9464 5.454600e+02 -3.128500e+02 +10 9465 1.067960e+03 -5.148900e+02 +20 9465 5.454600e+02 -3.128500e+02 +10 9466 1.080330e+03 -4.910699e+02 +17 9466 1.188370e+03 1.278900e+02 +18 9466 6.421001e+02 -1.196300e+02 +20 9466 5.581499e+02 -2.938700e+02 +10 9467 1.027680e+03 -4.804301e+02 +12 9467 4.488300e+02 -6.510699e+02 +20 9467 5.199301e+02 -2.873900e+02 +10 9468 1.065850e+03 -4.704500e+02 +12 9468 4.858199e+02 -6.413101e+02 +17 9468 1.146790e+03 1.719199e+02 +18 9468 6.266699e+02 -1.059200e+02 +20 9468 5.452300e+02 -2.808300e+02 +10 9469 9.671599e+02 -4.095000e+02 +17 9469 8.819800e+02 3.294099e+02 +10 9470 5.501101e+02 -3.955699e+02 +18 9470 2.172900e+02 -4.869995e+00 +10 9471 8.934700e+02 -3.655400e+02 +17 9471 3.396399e+02 4.507900e+02 +10 9472 8.934700e+02 -3.655400e+02 +17 9472 3.396399e+02 4.507900e+02 +10 9473 7.490801e+02 -3.473500e+02 +20 9473 3.630699e+02 -1.466100e+02 +10 9474 1.056970e+03 -3.347600e+02 +12 9474 4.827300e+02 -5.014700e+02 +17 9474 1.146990e+03 5.186300e+02 +18 9474 6.278101e+02 7.079956e+00 +20 9474 5.438999e+02 -1.855400e+02 +10 9475 1.056970e+03 -3.347600e+02 +12 9475 4.827300e+02 -5.014700e+02 +17 9475 1.146990e+03 5.186300e+02 +20 9475 5.438999e+02 -1.855400e+02 +10 9476 1.010320e+03 -3.025300e+02 +17 9476 8.640000e+02 5.976799e+02 +10 9477 1.436730e+03 -2.310500e+02 +12 9477 7.820000e+02 -4.125400e+02 +10 9478 -1.011980e+03 -2.208900e+02 +14 9478 1.141100e+02 3.031300e+02 +10 9479 9.392100e+02 -2.163400e+02 +12 9479 3.807900e+02 -3.652700e+02 +17 9479 8.011699e+02 8.319900e+02 +10 9480 1.589900e+03 -2.049600e+02 +12 9480 1.002670e+03 -3.918199e+02 +18 9480 1.066360e+03 8.756006e+01 +20 9480 9.114700e+02 -1.126300e+02 +10 9481 1.589900e+03 -2.049600e+02 +12 9481 1.002670e+03 -3.918199e+02 +18 9481 1.066360e+03 8.756006e+01 +20 9481 9.114700e+02 -1.126300e+02 +10 9482 1.687800e+03 -1.978700e+02 +20 9482 9.751101e+02 -1.114500e+02 +10 9483 1.717670e+03 -1.954700e+02 +12 9483 1.093170e+03 -3.894000e+02 +18 9483 1.143060e+03 8.827002e+01 +20 9483 9.945500e+02 -1.106200e+02 +10 9484 1.480440e+03 -1.646000e+02 +12 9484 9.012100e+02 -3.464800e+02 +20 9484 8.398799e+02 -8.106006e+01 +10 9485 -5.598199e+02 -1.420400e+02 +12 9485 -1.217530e+03 -2.108400e+02 +16 9485 1.800601e+02 5.418400e+02 +10 9486 1.270640e+03 -1.153900e+02 +12 9486 7.080300e+02 -2.819301e+02 +20 9486 7.017800e+02 -3.668994e+01 +10 9487 1.306990e+03 -1.120900e+02 +12 9487 7.386599e+02 -2.820500e+02 +20 9487 7.258401e+02 -3.627002e+01 +10 9488 1.522580e+03 -1.065699e+02 +12 9488 9.443601e+02 -2.898199e+02 +18 9488 1.020570e+03 1.709099e+02 +10 9489 1.382990e+03 -1.048800e+02 +12 9489 8.114900e+02 -2.789700e+02 +18 9489 9.096001e+02 1.814299e+02 +20 9489 7.775400e+02 -3.431006e+01 +10 9490 1.461860e+03 -9.896997e+01 +12 9490 8.864299e+02 -2.758000e+02 +18 9490 9.733601e+02 1.834299e+02 +20 9490 8.298899e+02 -3.238000e+01 +10 9491 1.537020e+03 -7.431995e+01 +12 9491 9.599800e+02 -2.566400e+02 +18 9491 1.035160e+03 1.992800e+02 +10 9492 1.253510e+03 -5.743005e+01 +18 9492 8.160000e+02 2.329299e+02 +20 9492 6.984299e+02 1.146002e+01 +10 9493 -1.533380e+03 1.046500e+02 +15 9493 5.509200e+02 5.150601e+02 +16 9493 -6.568300e+02 6.623300e+02 +19 9493 1.576899e+02 8.212500e+02 +20 9493 -1.384790e+03 1.776300e+02 +10 9494 -1.682020e+03 1.442400e+02 +16 9494 -7.585300e+02 6.832000e+02 +10 9495 2.212300e+02 1.067530e+03 +12 9495 -4.078600e+02 8.602200e+02 +20 9495 -1.385999e+01 7.643900e+02 +10 9496 9.768899e+02 -5.400000e+02 +17 9496 8.906001e+02 5.540039e+00 +10 9497 1.013520e+03 -5.383900e+02 +12 9497 4.328900e+02 -7.110800e+02 +20 9497 5.076200e+02 -3.276899e+02 +10 9498 1.797800e+02 -4.883199e+02 +16 9498 3.724800e+02 2.568500e+02 +18 9498 -1.103800e+02 -1.365900e+02 +20 9498 -8.184998e+01 -3.150601e+02 +10 9499 1.260830e+03 -4.731801e+02 +18 9499 7.817900e+02 -1.166500e+02 +20 9499 6.778501e+02 -2.894301e+02 +10 9500 -6.025000e+01 -4.683900e+02 +12 9500 -6.343300e+02 -5.672700e+02 +13 9500 -9.720400e+02 9.353003e+01 +10 9501 9.905000e+02 -4.661899e+02 +18 9501 5.660801e+02 -9.735999e+01 +10 9502 1.447350e+03 -4.652400e+02 +20 9502 8.044099e+02 -2.895100e+02 +10 9503 1.516610e+03 -4.619900e+02 +20 9503 8.498601e+02 -2.886801e+02 +10 9504 8.582400e+02 -4.588101e+02 +18 9504 4.935300e+02 -6.197998e+01 +20 9504 4.287700e+02 -2.453900e+02 +10 9505 -1.245720e+03 -4.562500e+02 +14 9505 -4.770999e+01 1.921400e+02 +10 9506 1.508630e+03 -4.497900e+02 +20 9506 8.433101e+02 -2.810800e+02 +10 9507 1.060390e+03 -3.902800e+02 +12 9507 4.836000e+02 -5.590200e+02 +17 9507 1.145580e+03 3.771300e+02 +18 9507 6.270901e+02 -3.877002e+01 +10 9508 1.595430e+03 -3.863900e+02 +12 9508 9.956699e+02 -5.757100e+02 +10 9509 1.101560e+03 -3.829800e+02 +12 9509 5.238400e+02 -5.528300e+02 +17 9509 1.249480e+03 3.945601e+02 +18 9509 6.591299e+02 -3.323999e+01 +20 9509 5.718301e+02 -2.195100e+02 +10 9510 1.101560e+03 -3.829800e+02 +12 9510 5.238400e+02 -5.528300e+02 +17 9510 1.249480e+03 3.945601e+02 +18 9510 6.591299e+02 -3.323999e+01 +20 9510 5.718301e+02 -2.195100e+02 +10 9511 1.001730e+03 -3.735699e+02 +12 9511 4.278900e+02 -5.395000e+02 +17 9511 9.858899e+02 4.226100e+02 +20 9511 5.040900e+02 -2.110200e+02 +10 9512 1.071790e+03 -3.514600e+02 +12 9512 4.963800e+02 -5.206100e+02 +17 9512 1.181360e+03 4.742700e+02 +18 9512 6.385601e+02 -8.479980e+00 +20 9512 5.536599e+02 -1.979100e+02 +10 9513 1.036010e+03 -3.007200e+02 +20 9513 5.305300e+02 -1.604700e+02 +10 9514 1.032940e+03 -2.883000e+02 +12 9514 4.616000e+02 -4.524100e+02 +17 9514 1.088760e+03 6.388900e+02 +20 9514 5.293199e+02 -1.511899e+02 +10 9515 9.595801e+02 -2.851000e+02 +12 9515 3.946801e+02 -4.464500e+02 +17 9515 8.831699e+02 6.632900e+02 +20 9515 4.800400e+02 -1.466200e+02 +10 9516 1.052990e+03 -2.437700e+02 +12 9516 4.828500e+02 -4.066700e+02 +17 9516 1.157960e+03 7.511799e+02 +18 9516 6.302900e+02 8.384009e+01 +20 9516 5.447200e+02 -1.202000e+02 +10 9517 9.846001e+02 -2.381300e+02 +12 9517 4.190100e+02 -3.961100e+02 +17 9517 9.682300e+02 7.770300e+02 +18 9517 5.760000e+02 9.232007e+01 +20 9517 4.981100e+02 -1.127400e+02 +10 9518 1.392930e+03 -2.332200e+02 +12 9518 8.139500e+02 -4.118700e+02 +20 9518 7.788999e+02 -1.248500e+02 +10 9519 -1.238910e+03 -2.273300e+02 +11 9519 -9.525200e+02 3.267300e+02 +10 9520 1.081970e+03 -2.190800e+02 +12 9520 5.114700e+02 -3.828400e+02 +10 9521 -1.027860e+03 -2.186000e+02 +14 9521 1.218600e+02 3.079200e+02 +16 9521 -1.360400e+02 4.559299e+02 +20 9521 -1.017370e+03 -3.187000e+01 +10 9522 1.139760e+03 -1.956300e+02 +12 9522 5.713701e+02 -3.606400e+02 +17 9522 1.389130e+03 8.697300e+02 +18 9522 7.048899e+02 1.194500e+02 +20 9522 6.067800e+02 -8.893005e+01 +10 9523 1.139760e+03 -1.956300e+02 +12 9523 5.713701e+02 -3.606400e+02 +17 9523 1.389130e+03 8.697300e+02 +18 9523 7.048899e+02 1.194500e+02 +20 9523 6.067800e+02 -8.893005e+01 +10 9524 -9.995700e+02 -1.373600e+02 +14 9524 1.361900e+02 3.567300e+02 +10 9525 -1.575850e+03 -1.374000e+02 +16 9525 -6.649200e+02 4.799900e+02 +10 9526 1.254850e+03 -1.093101e+02 +12 9526 6.903601e+02 -2.781500e+02 +18 9526 8.060400e+02 1.839299e+02 +20 9526 6.908501e+02 -3.342004e+01 +10 9527 1.557040e+03 -8.231006e+01 +12 9527 9.789299e+02 -2.651000e+02 +10 9528 1.258950e+03 -7.276001e+01 +18 9528 8.127100e+02 2.166200e+02 +10 9529 -1.241780e+03 -3.610999e+01 +16 9529 -4.231700e+02 5.791500e+02 +10 9530 -1.325840e+03 -1.552002e+01 +14 9530 -1.087400e+02 4.638201e+02 +16 9530 -4.966400e+02 5.895200e+02 +18 9530 -1.423900e+03 3.352800e+02 +10 9531 -1.323070e+03 1.015100e+02 +20 9531 -1.225410e+03 1.809900e+02 +10 9532 -1.552060e+03 1.904500e+02 +16 9532 -6.749900e+02 7.292500e+02 +20 9532 -1.402990e+03 2.465801e+02 +10 9533 -1.552060e+03 1.904500e+02 +16 9533 -6.749900e+02 7.292500e+02 +20 9533 -1.402990e+03 2.465801e+02 +10 9534 1.428700e+02 9.003799e+02 +12 9534 -5.079900e+02 6.738900e+02 +18 9534 -9.842004e+01 9.806499e+02 +10 9535 2.141400e+02 1.026750e+03 +12 9535 -4.244100e+02 8.077300e+02 +10 9536 1.442850e+03 -7.308700e+02 +18 9536 6.386299e+02 -3.731700e+02 +10 9537 1.084300e+03 -5.376500e+02 +18 9537 6.382200e+02 -1.612300e+02 +20 9537 5.558501e+02 -3.293400e+02 +10 9538 1.044070e+03 -5.252700e+02 +12 9538 4.618800e+02 -6.982700e+02 +20 9538 5.285800e+02 -3.192100e+02 +10 9539 1.000180e+03 -5.130200e+02 +12 9539 4.217400e+02 -6.834000e+02 +20 9539 4.991700e+02 -3.091200e+02 +10 9540 1.000180e+03 -5.130200e+02 +20 9540 4.991700e+02 -3.091200e+02 +10 9541 1.057760e+03 -4.846500e+02 +12 9541 4.767900e+02 -6.570100e+02 +17 9541 1.122290e+03 1.381000e+02 +20 9541 5.395701e+02 -2.908700e+02 +10 9542 9.930801e+02 -4.797700e+02 +18 9542 5.668501e+02 -1.084600e+02 +20 9542 4.957000e+02 -2.850699e+02 +10 9543 1.018280e+03 -4.502600e+02 +12 9543 4.420100e+02 -6.191500e+02 +10 9544 1.034510e+03 -4.498600e+02 +12 9544 4.571400e+02 -6.193600e+02 +17 9544 1.059220e+03 2.293401e+02 +20 9544 5.249200e+02 -2.657200e+02 +10 9545 1.026440e+03 -4.411801e+02 +20 9545 5.194100e+02 -2.595100e+02 +10 9546 6.797600e+02 -4.001600e+02 +18 9546 3.353700e+02 -7.709961e+00 +10 9547 8.386899e+02 -3.890500e+02 +18 9547 4.900300e+02 4.780029e+00 +10 9548 -1.223380e+03 -3.891300e+02 +14 9548 -6.700134e-01 2.260100e+02 +15 9548 8.797100e+02 1.507700e+02 +16 9548 -3.335900e+02 3.098000e+02 +10 9549 1.087120e+03 -3.845900e+02 +12 9549 5.104100e+02 -5.542300e+02 +17 9549 1.215620e+03 3.896300e+02 +18 9549 6.501699e+02 -3.569995e+01 +20 9549 5.636499e+02 -2.213900e+02 +10 9550 1.219900e+03 -3.779800e+02 +12 9550 6.398000e+02 -5.528700e+02 +17 9550 1.555180e+03 3.932500e+02 +18 9550 7.557500e+02 -3.640002e+01 +20 9550 6.541699e+02 -2.214700e+02 +10 9551 1.167710e+03 -3.769100e+02 +12 9551 5.884800e+02 -5.495800e+02 +17 9551 1.418920e+03 4.037800e+02 +18 9551 7.136201e+02 -3.234998e+01 +20 9551 6.180901e+02 -2.182900e+02 +10 9552 1.167710e+03 -3.769100e+02 +12 9552 5.884800e+02 -5.495800e+02 +17 9552 1.418920e+03 4.037800e+02 +18 9552 7.136201e+02 -3.234998e+01 +20 9552 6.180901e+02 -2.182900e+02 +10 9553 9.742900e+02 -3.764500e+02 +17 9553 9.105500e+02 4.198201e+02 +20 9553 4.859900e+02 -2.111300e+02 +10 9554 1.207720e+03 -3.748900e+02 +12 9554 6.292300e+02 -5.492200e+02 +17 9554 1.526030e+03 4.030300e+02 +18 9554 7.494199e+02 -3.245996e+01 +20 9554 6.479299e+02 -2.179100e+02 +10 9555 1.101740e+03 -3.587300e+02 +12 9555 5.263000e+02 -5.290200e+02 +10 9556 1.133890e+03 -3.573101e+02 +12 9556 5.569299e+02 -5.296000e+02 +17 9556 1.339390e+03 4.546599e+02 +18 9556 6.888999e+02 -1.652002e+01 +20 9556 5.965000e+02 -2.041500e+02 +10 9557 1.170230e+03 -3.550300e+02 +12 9557 5.927700e+02 -5.282400e+02 +17 9557 1.432540e+03 4.573000e+02 +18 9557 7.187100e+02 -1.605005e+01 +20 9557 6.214099e+02 -2.037500e+02 +10 9558 1.202600e+03 -3.526000e+02 +12 9558 6.250200e+02 -5.272100e+02 +20 9558 6.454700e+02 -2.020300e+02 +10 9559 -1.202300e+02 -3.470300e+02 +12 9559 -7.144000e+02 -4.420000e+02 +13 9559 -1.221640e+03 6.692800e+02 +18 9559 -3.718700e+02 6.258008e+01 +20 9559 -3.147500e+02 -1.434700e+02 +10 9560 1.213810e+03 -3.260699e+02 +12 9560 6.351001e+02 -5.006801e+02 +20 9560 6.519199e+02 -1.849100e+02 +10 9561 9.555200e+02 -3.235800e+02 +17 9561 8.623701e+02 5.559199e+02 +10 9562 9.555200e+02 -3.235800e+02 +12 9562 3.883400e+02 -4.824800e+02 +20 9562 4.746700e+02 -1.719399e+02 +10 9563 9.787000e+02 -2.512200e+02 +12 9563 4.126600e+02 -4.093500e+02 +18 9563 5.705400e+02 8.213000e+01 +20 9563 4.936500e+02 -1.216700e+02 +10 9564 9.787000e+02 -2.512200e+02 +12 9564 4.126600e+02 -4.093500e+02 +18 9564 5.705400e+02 8.213000e+01 +20 9564 4.936500e+02 -1.216700e+02 +10 9565 1.090940e+03 -2.465601e+02 +12 9565 5.204100e+02 -4.111801e+02 +17 9565 1.250600e+03 7.426799e+02 +18 9565 6.608501e+02 7.960999e+01 +20 9565 5.707400e+02 -1.238000e+02 +10 9566 -1.178300e+03 -2.205500e+02 +16 9566 -3.502800e+02 4.409500e+02 +10 9567 -1.055530e+03 -1.878900e+02 +14 9567 1.082700e+02 3.240000e+02 +18 9567 -1.244280e+03 2.256500e+02 +10 9568 1.390120e+03 -1.868199e+02 +12 9568 8.139800e+02 -3.648900e+02 +18 9568 9.088000e+02 1.128800e+02 +20 9568 7.787400e+02 -9.281006e+01 +10 9569 9.779199e+02 -1.871600e+02 +12 9569 4.159600e+02 -3.415800e+02 +10 9570 9.779199e+02 -1.871600e+02 +12 9570 4.159600e+02 -3.415800e+02 +10 9571 1.463000e+03 -1.810699e+02 +12 9571 8.837200e+02 -3.623600e+02 +18 9571 9.664500e+02 1.141000e+02 +20 9571 8.272900e+02 -9.142004e+01 +10 9572 1.463000e+03 -1.810699e+02 +12 9572 8.837200e+02 -3.623600e+02 +20 9572 8.272900e+02 -9.142004e+01 +10 9573 -5.038101e+02 -1.518500e+02 +18 9573 -7.106200e+02 2.344399e+02 +10 9574 -1.439300e+03 -1.467300e+02 +14 9574 -1.710400e+02 3.821000e+02 +16 9574 -5.694500e+02 4.814299e+02 +10 9575 -1.310150e+03 -1.141801e+02 +16 9575 -4.730800e+02 5.146000e+02 +10 9576 1.458610e+03 -6.488000e+01 +12 9576 8.919399e+02 -2.407600e+02 +20 9576 8.333301e+02 -7.919983e+00 +10 9577 -1.203240e+03 -3.305005e+01 +11 9577 -9.334900e+02 5.931100e+02 +14 9577 -2.673001e+01 4.505701e+02 +15 9577 8.282400e+02 4.445400e+02 +20 9577 -1.134420e+03 8.034998e+01 +10 9578 2.031100e+02 9.043599e+02 +12 9578 -4.443300e+02 6.782000e+02 +20 9578 -3.287000e+01 6.325900e+02 +10 9579 1.822900e+02 9.078101e+02 +12 9579 -4.653101e+02 6.846400e+02 +18 9579 -6.551001e+01 9.905300e+02 +10 9580 1.945601e+02 9.801599e+02 +12 9580 -4.448500e+02 7.647000e+02 +10 9581 1.872800e+02 9.906799e+02 +20 9581 -4.140002e+01 7.027600e+02 +10 9582 1.857700e+02 1.005250e+03 +12 9582 -4.495900e+02 7.921000e+02 +20 9582 -4.198999e+01 7.119200e+02 +10 9583 1.827400e+02 1.017220e+03 +12 9583 -4.520800e+02 8.092800e+02 +20 9583 -4.494995e+01 7.256300e+02 +10 9584 -1.246899e+02 -6.145200e+02 +12 9584 -8.515900e+02 -8.199200e+02 +10 9585 -2.122800e+02 -5.635400e+02 +18 9585 -4.509600e+02 -1.355200e+02 +10 9586 5.532400e+02 -5.245900e+02 +18 9586 2.176300e+02 -1.179000e+02 +20 9586 1.910200e+02 -2.963300e+02 +10 9587 1.083820e+03 -5.225699e+02 +17 9587 1.183880e+03 4.204004e+01 +18 9587 6.384299e+02 -1.491400e+02 +20 9587 5.557800e+02 -3.188700e+02 +10 9588 9.857900e+02 -5.137000e+02 +12 9588 4.089301e+02 -6.822000e+02 +20 9588 4.893900e+02 -3.089500e+02 +10 9589 1.014150e+03 -5.128199e+02 +20 9589 5.090400e+02 -3.094500e+02 +10 9590 1.981700e+02 -5.059100e+02 +13 9590 3.069900e+02 6.178003e+01 +16 9590 3.844301e+02 2.414600e+02 +10 9591 1.847400e+02 -5.058400e+02 +13 9591 2.525300e+02 6.226001e+01 +20 9591 -7.753003e+01 -3.274900e+02 +10 9592 6.839500e+02 -5.025601e+02 +12 9592 1.730601e+02 -6.363300e+02 +10 9593 1.083700e+03 -5.011400e+02 +17 9593 1.186780e+03 9.525000e+01 +20 9593 5.569299e+02 -3.039800e+02 +10 9594 1.083700e+03 -5.011400e+02 +18 9594 6.395200e+02 -1.332800e+02 +20 9594 5.569299e+02 -3.039800e+02 +10 9595 1.092510e+03 -4.943400e+02 +17 9595 1.209230e+03 1.106000e+02 +20 9595 5.629700e+02 -2.977700e+02 +10 9596 1.003650e+03 -4.891400e+02 +12 9596 4.258800e+02 -6.590400e+02 +20 9596 5.022700e+02 -2.920500e+02 +10 9597 6.745701e+02 -4.795300e+02 +12 9597 1.637100e+02 -6.122100e+02 +18 9597 3.272200e+02 -7.693005e+01 +20 9597 2.868400e+02 -2.594700e+02 +10 9598 1.081130e+03 -4.785601e+02 +17 9598 1.182740e+03 1.515100e+02 +18 9598 6.392400e+02 -1.138700e+02 +20 9598 5.554099e+02 -2.877400e+02 +10 9599 1.047690e+03 -4.792600e+02 +17 9599 1.097890e+03 1.526699e+02 +10 9600 1.247460e+03 -4.688300e+02 +12 9600 6.619500e+02 -6.476300e+02 +18 9600 7.733101e+02 -1.122300e+02 +20 9600 6.696101e+02 -2.858000e+02 +10 9601 3.100500e+02 -4.694100e+02 +13 9601 8.231299e+02 2.067000e+02 +20 9601 2.839966e+00 -3.053700e+02 +10 9602 1.560780e+03 -4.618000e+02 +12 9602 9.593301e+02 -6.514200e+02 +10 9603 1.605390e+03 -4.604500e+02 +12 9603 1.001390e+03 -6.519399e+02 +10 9604 9.689199e+02 -4.550300e+02 +12 9604 3.973600e+02 -6.214000e+02 +18 9604 5.519099e+02 -8.723999e+01 +20 9604 4.804000e+02 -2.665400e+02 +10 9605 1.633090e+03 -4.537100e+02 +12 9605 1.029880e+03 -6.486700e+02 +10 9606 -2.037800e+02 -4.499301e+02 +18 9606 -4.427500e+02 -3.565002e+01 +10 9607 1.222420e+03 -4.437900e+02 +12 9607 6.379099e+02 -6.209500e+02 +10 9608 1.108550e+03 -4.340900e+02 +12 9608 5.285100e+02 -6.063400e+02 +17 9608 1.257250e+03 2.622700e+02 +18 9608 6.642000e+02 -7.643994e+01 +20 9608 5.755300e+02 -2.570000e+02 +10 9609 5.203799e+02 -4.334800e+02 +12 9609 -2.143005e+01 -5.639000e+02 +20 9609 1.691801e+02 -2.263700e+02 +10 9610 1.645260e+03 -4.186200e+02 +20 9610 1.006070e+03 -2.620800e+02 +10 9611 1.630000e+03 -4.190800e+02 +12 9611 1.027830e+03 -6.093300e+02 +10 9612 9.009700e+02 -3.914200e+02 +17 9612 3.532500e+02 3.824700e+02 +10 9613 7.153101e+02 -3.892500e+02 +18 9613 3.826500e+02 1.468994e+01 +10 9614 9.772700e+02 -3.859301e+02 +12 9614 4.055900e+02 -5.498500e+02 +17 9614 9.192700e+02 3.950300e+02 +18 9614 5.618000e+02 -3.066003e+01 +20 9614 4.882000e+02 -2.179800e+02 +10 9615 7.216101e+02 -3.623700e+02 +18 9615 3.885900e+02 4.091003e+01 +20 9615 3.367300e+02 -1.582800e+02 +10 9616 1.542070e+03 -3.509000e+02 +12 9616 9.492500e+02 -5.386000e+02 +18 9616 1.015470e+03 -2.942004e+01 +20 9616 8.722400e+02 -2.127400e+02 +10 9617 1.542070e+03 -3.509000e+02 +12 9617 9.492500e+02 -5.386000e+02 +18 9617 1.015470e+03 -2.942004e+01 +20 9617 8.722400e+02 -2.127400e+02 +10 9618 8.695901e+02 -3.509200e+02 +18 9618 5.104900e+02 3.164001e+01 +10 9619 1.108350e+03 -3.415900e+02 +17 9619 1.273250e+03 4.963600e+02 +20 9619 5.794900e+02 -1.921899e+02 +10 9620 1.108350e+03 -3.415900e+02 +17 9620 1.273250e+03 4.963600e+02 +10 9621 1.195520e+03 -3.361300e+02 +12 9621 5.529500e+02 -5.153900e+02 +10 9622 -2.301200e+02 -3.328400e+02 +12 9622 -8.503900e+02 -4.381100e+02 +10 9623 1.044810e+03 -3.311400e+02 +12 9623 4.716100e+02 -4.973400e+02 +17 9623 1.115830e+03 5.306699e+02 +20 9623 5.357700e+02 -1.820100e+02 +10 9624 1.035430e+03 -2.980400e+02 +12 9624 4.642700e+02 -4.619100e+02 +17 9624 1.099390e+03 6.158800e+02 +18 9624 6.129299e+02 3.906006e+01 +20 9624 5.305500e+02 -1.579301e+02 +10 9625 6.421101e+02 -2.929399e+02 +12 9625 1.399399e+02 -3.982000e+02 +10 9626 1.106900e+03 -2.914900e+02 +17 9626 1.284910e+03 6.241699e+02 +18 9626 6.630701e+02 4.042004e+01 +20 9626 5.803401e+02 -1.565000e+02 +10 9627 1.121850e+03 -2.903600e+02 +12 9627 5.482600e+02 -4.585300e+02 +17 9627 1.326170e+03 6.255601e+02 +18 9627 6.834099e+02 4.040002e+01 +20 9627 5.937900e+02 -1.551200e+02 +10 9628 9.987800e+02 -2.797800e+02 +12 9628 3.860100e+02 -4.427500e+02 +10 9629 1.196280e+03 -2.777500e+02 +12 9629 6.218899e+02 -4.490800e+02 +17 9629 1.517320e+03 6.506599e+02 +18 9629 7.449199e+02 4.691003e+01 +20 9629 6.423799e+02 -1.500200e+02 +10 9630 1.594120e+03 -2.677300e+02 +12 9630 1.099830e+03 -4.527300e+02 +10 9631 1.079690e+03 -2.479800e+02 +12 9631 5.097600e+02 -4.128900e+02 +17 9631 1.222080e+03 7.417600e+02 +18 9631 6.523601e+02 7.757007e+01 +20 9631 5.633601e+02 -1.246700e+02 +10 9632 9.481201e+02 -2.339301e+02 +12 9632 3.840400e+02 -3.899900e+02 +17 9632 8.133201e+02 7.834200e+02 +18 9632 5.460100e+02 9.787000e+01 +20 9632 4.725900e+02 -1.080900e+02 +10 9633 1.125070e+03 -2.291801e+02 +12 9633 5.567900e+02 -3.944600e+02 +18 9633 6.923000e+02 9.265002e+01 +20 9633 5.965000e+02 -1.120699e+02 +10 9634 9.760400e+02 -2.290500e+02 +12 9634 4.138800e+02 -3.868800e+02 +18 9634 5.713301e+02 9.955005e+01 +20 9634 4.945500e+02 -1.066400e+02 +10 9635 9.786001e+02 -2.130300e+02 +12 9635 4.133500e+02 -3.653700e+02 +17 9635 9.547800e+02 8.451300e+02 +18 9635 5.724700e+02 1.139700e+02 +10 9636 9.786001e+02 -2.130300e+02 +12 9636 4.133500e+02 -3.653700e+02 +17 9636 9.547800e+02 8.451300e+02 +18 9636 5.724700e+02 1.139700e+02 +10 9637 1.032600e+03 -2.031200e+02 +12 9637 4.676700e+02 -3.629700e+02 +20 9637 5.327300e+02 -8.984998e+01 +10 9638 9.337800e+02 -2.004700e+02 +12 9638 3.812600e+02 -3.440000e+02 +17 9638 7.978701e+02 8.787000e+02 +18 9638 5.428999e+02 1.360601e+02 +10 9639 1.069840e+03 -1.994800e+02 +12 9639 5.036100e+02 -3.599800e+02 +17 9639 1.207990e+03 8.702300e+02 +18 9639 6.485200e+02 1.203201e+02 +20 9639 5.586599e+02 -8.880005e+01 +10 9640 1.344690e+03 -1.975601e+02 +12 9640 7.691799e+02 -3.740601e+02 +18 9640 8.701799e+02 1.062400e+02 +20 9640 7.468301e+02 -9.890002e+01 +10 9641 1.400350e+03 -1.932500e+02 +12 9641 8.224399e+02 -3.725900e+02 +18 9641 9.152200e+02 1.067100e+02 +20 9641 7.844199e+02 -9.798999e+01 +10 9642 9.457100e+02 -1.868700e+02 +12 9642 3.912100e+02 -3.410400e+02 +18 9642 5.499700e+02 1.382900e+02 +20 9642 4.750699e+02 -7.439001e+01 +10 9643 1.389400e+03 -1.701700e+02 +18 9643 9.088201e+02 1.275100e+02 +10 9644 1.161350e+03 -1.634900e+02 +12 9644 5.969399e+02 -3.290601e+02 +10 9645 1.069760e+03 -1.471700e+02 +20 9645 5.641299e+02 -5.173999e+01 +10 9646 -1.614410e+03 -1.347600e+02 +14 9646 -2.405400e+02 3.857500e+02 +10 9647 -1.327190e+03 -1.226700e+02 +14 9647 -4.838000e+01 3.861899e+02 +10 9648 -8.997500e+02 -1.179700e+02 +18 9648 -1.091700e+03 2.825601e+02 +10 9649 1.402160e+03 -1.081300e+02 +12 9649 8.305400e+02 -2.857000e+02 +18 9649 9.250100e+02 1.762500e+02 +10 9650 1.394630e+03 -9.852002e+01 +18 9650 9.198899e+02 1.843800e+02 +20 9650 7.866699e+02 -3.223999e+01 +10 9651 1.502250e+03 -9.189001e+01 +12 9651 9.276499e+02 -2.735000e+02 +20 9651 8.597600e+02 -3.066003e+01 +10 9652 1.306010e+03 -7.919995e+01 +18 9652 8.515300e+02 2.091500e+02 +20 9652 7.281899e+02 -1.200000e+01 +10 9653 1.379700e+03 -7.105005e+01 +20 9653 7.792800e+02 -9.080017e+00 +10 9654 1.379700e+03 -7.105005e+01 +18 9654 9.125000e+02 2.116300e+02 +20 9654 7.792800e+02 -9.080017e+00 +10 9655 1.415320e+03 -6.863000e+01 +12 9655 8.500200e+02 -2.435100e+02 +20 9655 8.029199e+02 -9.030029e+00 +10 9656 1.438960e+03 -6.482996e+01 +12 9656 8.722700e+02 -2.397400e+02 +10 9657 1.720930e+03 -5.381006e+01 +12 9657 1.131730e+03 -2.457700e+02 +10 9658 1.720930e+03 -5.381006e+01 +12 9658 1.131730e+03 -2.457700e+02 +20 9658 1.004620e+03 -1.140002e+01 +10 9659 1.532170e+03 2.547998e+01 +12 9659 9.618799e+02 -1.545699e+02 +20 9659 8.850500e+02 5.209998e+01 +10 9660 1.692600e+02 7.775000e+02 +12 9660 -4.815700e+02 5.607800e+02 +10 9661 2.399900e+02 9.066599e+02 +12 9661 -4.088400e+02 6.779600e+02 +18 9661 -1.891003e+01 9.853899e+02 +20 9661 -1.021997e+01 6.330300e+02 +10 9662 1.832700e+02 1.074440e+03 +12 9662 -4.488800e+02 8.681899e+02 +20 9662 -4.242004e+01 7.676700e+02 +10 9663 2.099301e+02 1.096460e+03 +12 9663 -4.204800e+02 8.911500e+02 +20 9663 -2.100000e+01 7.824800e+02 +10 9664 -1.722600e+02 -6.494000e+02 +12 9664 -8.994200e+02 -8.527800e+02 +10 9665 -1.506899e+02 -6.387100e+02 +12 9665 -8.785000e+02 -8.428800e+02 +10 9666 -1.506899e+02 -6.387100e+02 +12 9666 -8.785000e+02 -8.428800e+02 +10 9667 1.017380e+03 -5.491100e+02 +18 9667 5.841599e+02 -1.675699e+02 +20 9667 5.096100e+02 -3.351300e+02 +10 9668 1.000100e+03 -5.262500e+02 +12 9668 4.206700e+02 -6.978000e+02 +18 9668 5.719600e+02 -1.484600e+02 +20 9668 4.989100e+02 -3.187400e+02 +10 9669 1.195240e+03 -5.245601e+02 +12 9669 6.102500e+02 -7.031801e+02 +10 9670 1.065280e+03 -5.239500e+02 +18 9670 6.218401e+02 -1.501000e+02 +20 9670 5.429700e+02 -3.192200e+02 +10 9671 1.110170e+03 -5.230900e+02 +12 9671 5.258400e+02 -6.987700e+02 +17 9671 1.248680e+03 3.840002e+01 +10 9672 -1.562660e+03 -5.179100e+02 +16 9672 -5.123700e+02 2.105500e+02 +10 9673 1.093740e+03 -5.172000e+02 +17 9673 1.207290e+03 5.426001e+01 +18 9673 6.466799e+02 -1.450400e+02 +20 9673 5.623101e+02 -3.149000e+02 +10 9674 -1.504720e+03 -5.125900e+02 +19 9674 2.412000e+02 5.745996e+01 +10 9675 9.551001e+02 -4.912900e+02 +20 9675 4.698600e+02 -2.913000e+02 +10 9676 1.050860e+03 -4.867300e+02 +12 9676 4.707300e+02 -6.584800e+02 +18 9676 6.135801e+02 -1.180500e+02 +20 9676 5.340500e+02 -2.922500e+02 +10 9677 -2.898800e+02 -4.812800e+02 +12 9677 -9.253400e+02 -6.053800e+02 +10 9678 -1.257970e+03 -4.740000e+02 +11 9678 -9.494500e+02 -2.869995e+00 +14 9678 -5.413000e+01 1.819500e+02 +10 9679 1.284050e+03 -4.670400e+02 +12 9679 6.952900e+02 -6.470699e+02 +18 9679 8.027000e+02 -1.126100e+02 +20 9679 6.940100e+02 -2.858400e+02 +10 9680 1.011930e+03 -4.642200e+02 +18 9680 5.853201e+02 -9.707996e+01 +20 9680 5.095100e+02 -2.746400e+02 +10 9681 -1.227220e+03 -4.636400e+02 +11 9681 -9.206000e+02 1.169000e+01 +14 9681 -3.666000e+01 1.877100e+02 +15 9681 8.242800e+02 9.495001e+01 +10 9682 1.642560e+03 -4.592100e+02 +12 9682 1.035990e+03 -6.514000e+02 +10 9683 1.642560e+03 -4.592100e+02 +12 9683 1.035990e+03 -6.514000e+02 +10 9684 1.642560e+03 -4.592100e+02 +12 9684 1.035990e+03 -6.514000e+02 +10 9685 1.010270e+03 -4.583600e+02 +12 9685 4.310900e+02 -6.283500e+02 +18 9685 5.830000e+02 -9.320996e+01 +20 9685 5.079500e+02 -2.709500e+02 +10 9686 1.649010e+03 -4.539399e+02 +12 9686 1.042470e+03 -6.455100e+02 +10 9687 1.010030e+03 -4.430100e+02 +12 9687 4.343600e+02 -6.109600e+02 +17 9687 9.979600e+02 2.457500e+02 +18 9687 5.852200e+02 -8.053003e+01 +20 9687 5.086700e+02 -2.596300e+02 +10 9688 4.199600e+02 -4.409399e+02 +12 9688 -1.331000e+02 -5.712800e+02 +17 9688 -7.258000e+02 3.011699e+02 +18 9688 1.021600e+02 -4.285999e+01 +20 9688 9.479004e+01 -2.311400e+02 +10 9689 -1.267700e+02 -4.388300e+02 +12 9689 -7.267400e+02 -5.458500e+02 +10 9690 5.296201e+02 -4.325000e+02 +12 9690 -1.197998e+01 -5.639000e+02 +18 9690 1.977100e+02 -3.745996e+01 +10 9691 1.009380e+03 -4.319301e+02 +12 9691 4.341100e+02 -5.994600e+02 +17 9691 9.985801e+02 2.762000e+02 +20 9691 5.084500e+02 -2.519000e+02 +10 9692 6.308401e+02 -4.292000e+02 +20 9692 2.517100e+02 -2.255400e+02 +10 9693 -7.827002e+01 -4.264100e+02 +13 9693 -1.046790e+03 2.913301e+02 +18 9693 -3.397200e+02 6.700439e-01 +20 9693 -2.874399e+02 -1.970800e+02 +10 9694 -3.240400e+02 -4.119301e+02 +12 9694 -9.630700e+02 -5.281700e+02 +10 9695 1.599560e+03 -4.067400e+02 +12 9695 9.992500e+02 -5.972100e+02 +10 9696 9.083000e+02 -4.058400e+02 +17 9696 3.741101e+02 3.461000e+02 +10 9697 -2.699900e+02 -4.019100e+02 +12 9697 -9.001600e+02 -5.171600e+02 +10 9698 -2.907000e+02 -4.020200e+02 +12 9698 -9.229600e+02 -5.176100e+02 +10 9699 1.031970e+03 -3.992800e+02 +20 9699 5.246700e+02 -2.297800e+02 +10 9700 7.128899e+02 -3.976600e+02 +20 9700 3.288101e+02 -1.860000e+02 +10 9701 -1.388800e+02 -3.966700e+02 +12 9701 -7.400700e+02 -5.002000e+02 +13 9701 -1.310670e+03 4.479199e+02 +10 9702 8.868000e+02 -3.855200e+02 +17 9702 3.219800e+02 3.983500e+02 +10 9703 6.271599e+02 -3.708199e+02 +12 9703 9.806006e+01 -4.988700e+02 +18 9703 2.852000e+02 1.323999e+01 +10 9704 1.100150e+03 -3.572600e+02 +17 9704 1.248960e+03 4.590300e+02 +20 9704 5.717000e+02 -2.018300e+02 +10 9705 4.793701e+02 -3.391300e+02 +18 9705 1.573000e+02 4.529004e+01 +20 9705 1.407200e+02 -1.558500e+02 +10 9706 1.226120e+03 -3.344900e+02 +12 9706 6.481001e+02 -5.100200e+02 +17 9706 1.581750e+03 5.017800e+02 +18 9706 7.649500e+02 -2.079956e+00 +20 9706 6.604399e+02 -1.915400e+02 +10 9707 1.027770e+03 -3.300699e+02 +12 9707 4.566100e+02 -4.940699e+02 +17 9707 1.070480e+03 5.350701e+02 +18 9707 6.062300e+02 1.360999e+01 +20 9707 5.254500e+02 -1.796000e+02 +10 9708 1.034380e+03 -3.273000e+02 +18 9708 6.099900e+02 1.564001e+01 +20 9708 5.287100e+02 -1.786500e+02 +10 9709 4.226499e+02 -3.235200e+02 +12 9709 -1.861000e+02 -4.439800e+02 +18 9709 1.084700e+02 5.940991e+01 +10 9710 -2.331300e+02 -3.059800e+02 +18 9710 -4.648700e+02 8.819995e+01 +20 9710 -3.936700e+02 -1.218900e+02 +10 9711 9.615400e+02 -2.975200e+02 +12 9711 3.954399e+02 -4.558500e+02 +17 9711 8.878799e+02 6.241200e+02 +18 9711 5.536799e+02 4.405005e+01 +20 9711 4.797100e+02 -1.537900e+02 +10 9712 1.012520e+03 -2.957100e+02 +12 9712 4.417700e+02 -4.582000e+02 +17 9712 1.035430e+03 6.242000e+02 +18 9712 5.945701e+02 4.206995e+01 +20 9712 5.150100e+02 -1.553600e+02 +10 9713 1.061740e+03 -2.950100e+02 +18 9713 6.343501e+02 3.942004e+01 +20 9713 5.488000e+02 -1.573900e+02 +10 9714 6.889800e+02 -2.949600e+02 +12 9714 2.339600e+02 -3.866300e+02 +20 9714 3.138900e+02 -1.050500e+02 +10 9715 9.578301e+02 -2.906801e+02 +18 9715 5.519500e+02 4.994995e+01 +20 9715 4.778300e+02 -1.494200e+02 +10 9716 9.578301e+02 -2.906801e+02 +12 9716 4.375800e+02 -4.468101e+02 +17 9716 8.702000e+02 6.412600e+02 +20 9716 5.106899e+02 -1.482200e+02 +10 9717 1.537520e+03 -2.901100e+02 +20 9717 8.724199e+02 -1.701300e+02 +10 9718 1.135670e+03 -2.891400e+02 +12 9718 5.610701e+02 -4.580100e+02 +17 9718 1.361720e+03 6.273600e+02 +18 9718 6.943101e+02 4.050000e+01 +20 9718 5.997300e+02 -1.559900e+02 +10 9719 1.569060e+03 -2.882600e+02 +20 9719 8.932000e+02 -1.701300e+02 +10 9720 1.165770e+03 -2.877800e+02 +12 9720 5.902600e+02 -4.578800e+02 +17 9720 1.442250e+03 6.279900e+02 +20 9720 6.203201e+02 -1.561400e+02 +10 9721 1.088270e+03 -2.848700e+02 +12 9721 5.160200e+02 -4.517900e+02 +20 9721 5.670500e+02 -1.507500e+02 +10 9722 1.003060e+03 -2.500100e+02 +12 9722 4.354200e+02 -4.093101e+02 +20 9722 5.095601e+02 -1.217700e+02 +10 9723 1.149300e+03 -2.461801e+02 +12 9723 5.786499e+02 -4.141700e+02 +17 9723 1.403930e+03 7.371899e+02 +18 9723 7.092400e+02 7.584998e+01 +10 9724 1.482240e+03 -2.300800e+02 +12 9724 8.990601e+02 -4.136100e+02 +20 9724 8.380400e+02 -1.269200e+02 +10 9725 -1.263040e+03 -2.179301e+02 +20 9725 -1.174450e+03 -6.431006e+01 +10 9726 -1.274650e+03 -2.128900e+02 +11 9726 -9.924900e+02 3.388200e+02 +10 9727 9.627800e+02 -2.115200e+02 +18 9727 5.594800e+02 1.163101e+02 +10 9728 9.696101e+02 -2.104200e+02 +12 9728 4.058800e+02 -3.658800e+02 +17 9728 9.302400e+02 8.513600e+02 +18 9728 5.660601e+02 1.165200e+02 +10 9729 -2.564800e+02 -2.073500e+02 +12 9729 -8.769800e+02 -3.010300e+02 +10 9730 1.739400e+03 -2.039600e+02 +12 9730 1.140770e+03 -3.972500e+02 +20 9730 1.008830e+03 -1.171500e+02 +10 9731 -5.293700e+02 -2.044100e+02 +18 9731 -7.271300e+02 1.824099e+02 +10 9732 1.302280e+03 -2.018101e+02 +18 9732 8.357100e+02 1.043600e+02 +20 9732 7.180801e+02 -1.006600e+02 +10 9733 1.024600e+03 -1.976899e+02 +12 9733 4.594000e+02 -3.567300e+02 +10 9734 -5.279500e+02 -1.927000e+02 +12 9734 -1.186720e+03 -2.768600e+02 +10 9735 -1.163430e+03 -1.928600e+02 +16 9735 -3.368700e+02 4.641799e+02 +20 9735 -1.107380e+03 -4.059998e+01 +10 9736 1.514120e+03 -1.917200e+02 +12 9736 9.327800e+02 -3.752700e+02 +18 9736 1.008150e+03 1.027900e+02 +20 9736 8.620000e+02 -1.007600e+02 +10 9737 1.093820e+03 -1.691200e+02 +12 9737 5.300200e+02 -3.303300e+02 +17 9737 1.268370e+03 9.442500e+02 +10 9738 1.053320e+03 -1.664500e+02 +12 9738 4.888400e+02 -3.261300e+02 +17 9738 1.168690e+03 9.569600e+02 +18 9738 6.358000e+02 1.487200e+02 +20 9738 5.477700e+02 -6.457996e+01 +10 9739 -1.212770e+03 -1.432500e+02 +16 9739 -3.888500e+02 4.988000e+02 +10 9740 -1.212770e+03 -1.432500e+02 +16 9740 -3.888500e+02 4.988000e+02 +10 9741 1.386820e+03 -1.378900e+02 +20 9741 7.789700e+02 -5.784998e+01 +10 9742 -1.282080e+03 -1.363700e+02 +14 9742 -7.645001e+01 3.883101e+02 +10 9743 -1.282080e+03 -1.363700e+02 +11 9743 -1.011320e+03 4.423800e+02 +10 9744 1.534970e+03 -1.075400e+02 +12 9744 9.561799e+02 -2.907100e+02 +20 9744 8.793799e+02 -4.241003e+01 +10 9745 1.508520e+03 -8.842004e+01 +18 9745 1.011330e+03 1.882600e+02 +20 9745 8.631699e+02 -2.851001e+01 +10 9746 1.265070e+03 -8.317004e+01 +12 9746 7.033201e+02 -2.501100e+02 +18 9746 8.166101e+02 2.074800e+02 +10 9747 1.564200e+03 -6.706006e+01 +12 9747 9.870100e+02 -2.518700e+02 +20 9747 9.008000e+02 -1.492999e+01 +10 9748 1.647300e+03 -5.975000e+01 +12 9748 1.064640e+03 -2.486801e+02 +20 9748 9.556899e+02 -1.310999e+01 +10 9749 -1.247130e+03 -5.382996e+01 +16 9749 -4.256700e+02 5.649299e+02 +10 9750 9.456499e+02 -4.942004e+01 +20 9750 4.820601e+02 2.363000e+01 +10 9751 1.541420e+03 -4.322998e+01 +12 9751 9.823101e+02 -2.248700e+02 +10 9752 1.588540e+03 -3.876001e+01 +12 9752 1.009550e+03 -2.234800e+02 +10 9753 1.609680e+03 -3.672998e+01 +12 9753 1.110190e+03 -2.189700e+02 +10 9754 1.487670e+03 -3.363000e+01 +20 9754 8.547900e+02 1.404999e+01 +10 9755 -1.213520e+03 -9.819946e+00 +14 9755 -3.541000e+01 4.663800e+02 +10 9756 -1.203380e+03 5.319946e+00 +11 9756 -9.397200e+02 6.459200e+02 +10 9757 -1.297560e+03 1.068994e+01 +14 9757 -9.028000e+01 4.806200e+02 +10 9758 -1.434730e+03 2.693005e+01 +15 9758 4.152300e+02 4.528400e+02 +16 9758 -7.955500e+02 6.071899e+02 +10 9759 -1.425430e+03 8.523999e+01 +14 9759 -1.671900e+02 5.228900e+02 +10 9760 -1.258840e+03 9.239001e+01 +15 9760 7.674600e+02 5.405500e+02 +16 9760 -4.479900e+02 6.784301e+02 +10 9761 2.016300e+02 7.631500e+02 +12 9761 -4.541400e+02 5.342300e+02 +18 9761 -5.396997e+01 8.624800e+02 +20 9761 -3.893994e+01 5.315100e+02 +10 9762 2.767000e+02 7.821500e+02 +18 9762 8.380005e+00 8.830701e+02 +20 9762 1.345996e+01 5.484299e+02 +10 9763 1.919600e+02 9.985801e+02 +20 9763 -3.797998e+01 7.078800e+02 +10 9764 1.720300e+02 1.016310e+03 +12 9764 -4.621100e+02 8.097700e+02 +20 9764 -5.202002e+01 7.257100e+02 +10 9765 1.693500e+02 1.024020e+03 +12 9765 -4.644000e+02 8.159399e+02 +20 9765 -5.356995e+01 7.309900e+02 +10 9766 1.892400e+02 1.082860e+03 +20 9766 -3.797998e+01 7.746700e+02 +10 9767 1.892400e+02 1.082860e+03 +12 9767 -4.405800e+02 8.784200e+02 +20 9767 -3.797998e+01 7.746700e+02 +10 9768 1.872600e+02 1.090150e+03 +12 9768 -4.444000e+02 8.849000e+02 +10 9769 9.649500e+02 -5.155400e+02 +20 9769 4.762000e+02 -3.094800e+02 +10 9770 1.082280e+03 -5.136700e+02 +17 9770 1.180860e+03 6.356995e+01 +18 9770 6.380601e+02 -1.418400e+02 +20 9770 5.551599e+02 -3.123800e+02 +10 9771 1.112030e+03 -5.124600e+02 +12 9771 5.293199e+02 -6.878199e+02 +17 9771 1.255180e+03 6.443005e+01 +10 9772 1.086960e+03 -5.103500e+02 +17 9772 1.192060e+03 7.306995e+01 +18 9772 6.417100e+02 -1.389100e+02 +10 9773 1.911801e+02 -4.989399e+02 +12 9773 -5.313300e+02 -7.042000e+02 +13 9773 2.781600e+02 9.262000e+01 +18 9773 -1.006200e+02 -1.453600e+02 +10 9774 1.044970e+03 -4.975601e+02 +17 9774 1.082260e+03 1.063500e+02 +20 9774 5.305000e+02 -2.994500e+02 +10 9775 9.850200e+02 -4.887700e+02 +17 9775 9.217800e+02 1.327400e+02 +20 9775 4.896100e+02 -2.909600e+02 +10 9776 1.010830e+03 -4.827200e+02 +18 9776 5.828301e+02 -1.129100e+02 +20 9776 5.076600e+02 -2.881400e+02 +10 9777 -1.209940e+03 -4.689900e+02 +11 9777 -8.975000e+02 6.880005e+00 +14 9777 -2.437000e+01 1.834800e+02 +15 9777 8.413101e+02 8.976001e+01 +10 9778 9.615601e+02 -4.661100e+02 +17 9778 8.536599e+02 1.924099e+02 +18 9778 5.456499e+02 -9.534998e+01 +20 9778 4.751400e+02 -2.735601e+02 +10 9779 9.615601e+02 -4.661100e+02 +17 9779 8.536599e+02 1.924099e+02 +10 9780 9.622700e+02 -4.611500e+02 +20 9780 4.753300e+02 -2.705200e+02 +10 9781 -1.296680e+03 -4.556200e+02 +11 9781 -9.963500e+02 1.750000e+01 +10 9782 -2.900699e+02 -4.545800e+02 +12 9782 -9.246300e+02 -5.767800e+02 +18 9782 -5.154100e+02 -4.295996e+01 +10 9783 -1.446700e+02 -4.097200e+02 +13 9783 -1.337710e+03 3.902000e+02 +18 9783 -3.930500e+02 2.630005e+00 +20 9783 -3.325400e+02 -1.952800e+02 +10 9784 4.894800e+02 -4.039800e+02 +13 9784 1.542180e+03 3.405100e+02 +20 9784 1.473900e+02 -2.038900e+02 +10 9785 1.450250e+03 -4.010601e+02 +20 9785 8.085300e+02 -2.446899e+02 +10 9786 -1.978500e+02 -3.808000e+02 +12 9786 -8.123500e+02 -4.884301e+02 +13 9786 -1.576670e+03 5.372900e+02 +10 9787 -3.262500e+02 -3.788900e+02 +12 9787 -9.637900e+02 -4.920500e+02 +10 9788 9.092500e+02 -3.684399e+02 +17 9788 3.781699e+02 4.413101e+02 +10 9789 9.608301e+02 -3.586801e+02 +12 9789 3.932000e+02 -5.206500e+02 +17 9789 8.659900e+02 4.634299e+02 +18 9789 5.513401e+02 -6.430054e+00 +20 9789 4.778600e+02 -1.978900e+02 +10 9790 -1.211310e+03 -3.576600e+02 +20 9790 -1.136610e+03 -1.704700e+02 +10 9791 -1.269070e+03 -3.457600e+02 +14 9791 -6.417999e+01 2.596600e+02 +15 9791 7.815400e+02 1.865900e+02 +10 9792 1.008280e+03 -3.310400e+02 +12 9792 4.369000e+02 -4.944301e+02 +17 9792 1.010380e+03 5.346799e+02 +20 9792 5.106700e+02 -1.804100e+02 +10 9793 1.008280e+03 -3.310400e+02 +12 9793 4.369000e+02 -4.944301e+02 +20 9793 5.106700e+02 -1.804100e+02 +10 9794 1.117960e+03 -3.074200e+02 +18 9794 6.793899e+02 2.619995e+01 +10 9795 1.142290e+03 -3.060300e+02 +12 9795 5.672600e+02 -4.757400e+02 +17 9795 1.373610e+03 5.839800e+02 +18 9795 6.984600e+02 2.625000e+01 +20 9795 6.035500e+02 -1.680601e+02 +10 9796 1.142290e+03 -3.060300e+02 +12 9796 5.672600e+02 -4.757400e+02 +17 9796 1.373610e+03 5.839800e+02 +18 9796 6.984600e+02 2.625000e+01 +20 9796 6.035500e+02 -1.680601e+02 +10 9797 9.531299e+02 -3.014500e+02 +12 9797 3.862700e+02 -4.600699e+02 +17 9797 8.595200e+02 6.162300e+02 +18 9797 5.467800e+02 4.106995e+01 +20 9797 4.741700e+02 -1.567100e+02 +10 9798 1.051650e+03 -3.004600e+02 +12 9798 4.789800e+02 -4.661600e+02 +17 9798 1.141480e+03 6.074000e+02 +18 9798 6.256399e+02 3.527002e+01 +20 9798 5.414299e+02 -1.614500e+02 +10 9799 6.975801e+02 -2.990900e+02 +20 9799 3.181700e+02 -1.086500e+02 +10 9800 1.191270e+03 -2.962500e+02 +18 9800 7.358000e+02 3.172998e+01 +10 9801 7.031899e+02 -2.939301e+02 +12 9801 2.519200e+02 -3.858900e+02 +18 9801 3.762000e+02 1.022300e+02 +10 9802 7.031899e+02 -2.939301e+02 +12 9802 2.519200e+02 -3.858900e+02 +18 9802 3.762000e+02 1.022300e+02 +20 9802 3.251600e+02 -1.050300e+02 +10 9803 7.089900e+02 -2.934600e+02 +18 9803 3.812600e+02 1.025901e+02 +20 9803 3.293400e+02 -1.043700e+02 +10 9804 1.006070e+03 -2.856300e+02 +12 9804 4.375800e+02 -4.468101e+02 +17 9804 1.013060e+03 6.493401e+02 +20 9804 5.106899e+02 -1.482200e+02 +10 9805 1.006070e+03 -2.856300e+02 +17 9805 1.013060e+03 6.493401e+02 +10 9806 -3.970200e+02 -2.845699e+02 +16 9806 2.894100e+02 4.275400e+02 +10 9807 1.221170e+03 -2.833700e+02 +12 9807 6.452400e+02 -4.564100e+02 +17 9807 1.584120e+03 6.343101e+02 +18 9807 7.641101e+02 4.098999e+01 +20 9807 6.593799e+02 -1.551200e+02 +10 9808 -2.404000e+02 -2.826600e+02 +12 9808 -8.610200e+02 -3.833101e+02 +18 9808 -4.703800e+02 1.085801e+02 +10 9809 -1.086130e+03 -2.801899e+02 +11 9809 -8.353300e+02 3.116200e+02 +20 9809 -1.064290e+03 -7.780005e+01 +10 9810 1.215360e+03 -2.787600e+02 +12 9810 6.394199e+02 -4.510200e+02 +17 9810 1.569710e+03 6.463700e+02 +18 9810 7.596101e+02 4.514001e+01 +20 9810 6.555400e+02 -1.513400e+02 +10 9811 1.203590e+03 -2.789000e+02 +12 9811 6.296499e+02 -4.510100e+02 +17 9811 1.537840e+03 6.466100e+02 +18 9811 7.513000e+02 4.515002e+01 +20 9811 6.475801e+02 -1.510800e+02 +10 9812 -1.039610e+03 -2.739200e+02 +14 9812 1.162100e+02 2.755000e+02 +20 9812 -1.054170e+03 -7.714001e+01 +10 9813 7.043501e+02 -2.729100e+02 +18 9813 3.776801e+02 1.218301e+02 +20 9813 3.256100e+02 -8.816003e+01 +10 9814 6.949700e+02 -2.721600e+02 +18 9814 3.695300e+02 1.226899e+02 +20 9814 3.193000e+02 -8.718994e+01 +10 9815 7.130801e+02 -2.712200e+02 +12 9815 2.635000e+02 -3.605000e+02 +18 9815 3.859000e+02 1.229900e+02 +10 9816 1.702990e+03 -2.631801e+02 +12 9816 1.202490e+03 -4.519399e+02 +10 9817 9.977300e+02 -2.570100e+02 +12 9817 4.308800e+02 -4.171200e+02 +20 9817 5.067600e+02 -1.270500e+02 +10 9818 2.644600e+02 -2.547200e+02 +16 9818 4.020500e+02 4.680000e+02 +10 9819 9.624500e+02 -2.538900e+02 +17 9819 8.977200e+02 7.354200e+02 +20 9819 4.824700e+02 -1.232100e+02 +10 9820 1.022680e+03 -2.470500e+02 +12 9820 4.545300e+02 -4.083101e+02 +10 9821 4.583799e+02 -2.370699e+02 +13 9821 1.415360e+03 1.081360e+03 +17 9821 -7.769800e+02 8.472400e+02 +10 9822 -2.503199e+02 -2.336000e+02 +12 9822 -8.705000e+02 -3.295200e+02 +10 9823 -2.503199e+02 -2.336000e+02 +12 9823 -8.705000e+02 -3.295200e+02 +20 9823 -4.061801e+02 -6.693994e+01 +10 9824 9.712600e+02 -2.205400e+02 +12 9824 4.075200e+02 -3.764600e+02 +18 9824 5.663799e+02 1.081100e+02 +20 9824 4.898199e+02 -9.927002e+01 +10 9825 -3.069200e+02 -2.205100e+02 +18 9825 -5.276500e+02 1.619199e+02 +10 9826 -1.200660e+03 -2.163600e+02 +14 9826 -2.167001e+01 3.365000e+02 +15 9826 8.402100e+02 2.941700e+02 +16 9826 -3.743100e+02 4.433300e+02 +10 9827 -2.255000e+02 -2.149600e+02 +20 9827 -3.866200e+02 -5.168005e+01 +10 9828 1.035670e+03 -2.131100e+02 +12 9828 4.698101e+02 -3.734700e+02 +17 9828 1.110800e+03 8.358000e+02 +20 9828 5.344100e+02 -9.752002e+01 +10 9829 -3.350000e+02 -1.999500e+02 +18 9829 -5.526500e+02 1.809600e+02 +10 9830 -3.350000e+02 -1.999500e+02 +18 9830 -5.526500e+02 1.809600e+02 +10 9831 1.012610e+03 -1.985200e+02 +17 9831 1.051410e+03 8.771799e+02 +10 9832 1.388210e+03 -1.956801e+02 +12 9832 8.119099e+02 -3.743000e+02 +18 9832 9.060200e+02 1.051799e+02 +20 9832 7.766101e+02 -9.931995e+01 +10 9833 -3.021899e+02 -1.962000e+02 +12 9833 -9.289000e+02 -2.894399e+02 +10 9834 1.615290e+03 -1.938500e+02 +12 9834 1.027900e+03 -3.815699e+02 +18 9834 1.087220e+03 9.590991e+01 +20 9834 9.288899e+02 -1.057200e+02 +10 9835 1.432530e+03 -1.925200e+02 +12 9835 8.539600e+02 -3.729301e+02 +18 9835 9.418000e+02 1.056599e+02 +20 9835 8.067000e+02 -9.853003e+01 +10 9836 9.840100e+02 -1.928400e+02 +12 9836 4.222500e+02 -3.490500e+02 +10 9837 1.663860e+03 -1.899399e+02 +12 9837 1.070820e+03 -3.798700e+02 +18 9837 1.124480e+03 9.676001e+01 +20 9837 9.599299e+02 -1.047100e+02 +10 9838 1.481890e+03 -1.890500e+02 +12 9838 9.003301e+02 -3.717500e+02 +20 9838 8.396201e+02 -9.802002e+01 +10 9839 -7.603500e+02 -1.821600e+02 +12 9839 -1.457250e+03 -2.402000e+02 +10 9840 -1.245030e+03 -1.749700e+02 +11 9840 -9.643100e+02 3.923101e+02 +14 9840 -5.131000e+01 3.634600e+02 +10 9841 -1.238410e+03 -1.723800e+02 +20 9841 -1.157520e+03 -2.994995e+01 +10 9842 -1.207600e+03 -1.597200e+02 +14 9842 -2.692001e+01 3.731000e+02 +10 9843 -8.042200e+02 -1.581200e+02 +14 9843 2.466100e+02 3.519300e+02 +16 9843 1.339001e+01 5.145800e+02 +19 9843 1.367480e+03 5.465801e+02 +10 9844 -8.704600e+02 -1.583400e+02 +20 9844 -9.096500e+02 1.090002e+01 +10 9845 -1.381820e+03 -1.513800e+02 +15 9845 6.769301e+02 3.332700e+02 +19 9845 3.631400e+02 5.242300e+02 +20 9845 -1.261210e+03 -1.871002e+01 +10 9846 1.518780e+03 -1.246400e+02 +12 9846 9.405601e+02 -3.069600e+02 +20 9846 8.681799e+02 -5.390002e+01 +10 9847 -1.216910e+03 -1.193700e+02 +16 9847 -3.946700e+02 5.170000e+02 +10 9848 3.070601e+02 -1.132000e+02 +16 9848 5.088800e+02 6.085500e+02 +10 9849 1.508200e+03 -1.021100e+02 +12 9849 9.316799e+02 -2.840400e+02 +18 9849 1.010390e+03 1.773700e+02 +20 9849 8.623701e+02 -3.756995e+01 +10 9850 1.241290e+03 -8.213000e+01 +18 9850 7.975500e+02 2.100400e+02 +10 9851 -1.172880e+03 -3.200000e+01 +16 9851 -3.602400e+02 5.883700e+02 +10 9852 1.386000e+02 8.183600e+02 +20 9852 -8.082996e+01 5.867000e+02 +10 9853 2.141000e+02 9.104199e+02 +12 9853 -4.387200e+02 6.806200e+02 +18 9853 -3.796997e+01 9.877000e+02 +20 9853 -2.704004e+01 6.347100e+02 +10 9854 2.408900e+02 1.003450e+03 +20 9854 -4.719971e+00 7.100100e+02 +10 9855 1.764100e+02 1.007080e+03 +12 9855 -4.585900e+02 7.993000e+02 +20 9855 -4.909998e+01 7.184299e+02 +10 9856 1.764100e+02 1.007080e+03 +12 9856 -4.585900e+02 7.993000e+02 +20 9856 -4.909998e+01 7.184299e+02 +10 9857 -1.301000e+02 -6.193500e+02 +12 9857 -8.570500e+02 -8.243300e+02 +10 9858 -1.301000e+02 -6.193500e+02 +12 9858 -8.570500e+02 -8.243300e+02 +10 9859 -2.159900e+02 -5.803199e+02 +12 9859 -8.428400e+02 -7.141500e+02 +10 9860 -2.159900e+02 -5.803199e+02 +20 9860 -3.854301e+02 -3.287400e+02 +10 9861 -2.200000e+02 -5.735500e+02 +18 9861 -4.577400e+02 -1.446300e+02 +20 9861 -3.879301e+02 -3.233101e+02 +10 9862 -1.483199e+02 -5.528900e+02 +12 9862 -8.716100e+02 -7.625000e+02 +10 9863 -1.483199e+02 -5.528900e+02 +12 9863 -8.716100e+02 -7.625000e+02 +10 9864 -2.388199e+02 -5.459100e+02 +12 9864 -8.686800e+02 -6.764900e+02 +10 9865 -6.442004e+01 -5.443700e+02 +12 9865 -7.488700e+02 -7.259100e+02 +10 9866 1.085470e+03 -5.405699e+02 +18 9866 6.392500e+02 -1.640800e+02 +20 9866 5.567100e+02 -3.316100e+02 +10 9867 1.064620e+03 -5.371600e+02 +12 9867 4.823900e+02 -7.114399e+02 +18 9867 6.223799e+02 -1.604200e+02 +20 9867 5.424800e+02 -3.283700e+02 +10 9868 1.068370e+03 -5.344900e+02 +12 9868 4.853900e+02 -7.089301e+02 +18 9868 6.256499e+02 -1.581500e+02 +10 9869 1.068370e+03 -5.344900e+02 +18 9869 6.256499e+02 -1.581500e+02 +10 9870 -2.239399e+02 -5.342100e+02 +12 9870 -8.503300e+02 -6.618101e+02 +10 9871 1.085730e+03 -5.339700e+02 +17 9871 1.186360e+03 1.282996e+01 +18 9871 6.394900e+02 -1.584000e+02 +20 9871 5.569299e+02 -3.268101e+02 +10 9872 9.899399e+02 -5.271200e+02 +12 9872 4.117000e+02 -6.979900e+02 +17 9872 9.346001e+02 3.529004e+01 +18 9872 5.639600e+02 -1.486300e+02 +10 9873 4.739800e+02 -5.119301e+02 +12 9873 -7.814001e+01 -6.510000e+02 +17 9873 -5.877700e+02 1.075400e+02 +18 9873 1.458199e+02 -1.054900e+02 +20 9873 1.323000e+02 -2.852900e+02 +10 9874 4.680100e+02 -5.119500e+02 +12 9874 -8.494995e+01 -6.507500e+02 +20 9874 1.279399e+02 -2.854301e+02 +10 9875 -2.349000e+02 -5.065400e+02 +12 9875 -8.635200e+02 -6.385400e+02 +10 9876 5.377500e+02 -5.052300e+02 +20 9876 1.806400e+02 -2.823500e+02 +10 9877 1.098190e+03 -4.838500e+02 +12 9877 5.170500e+02 -6.574301e+02 +17 9877 1.224900e+03 1.370900e+02 +18 9877 6.524600e+02 -1.179301e+02 +10 9878 -2.223000e+02 -4.812700e+02 +12 9878 -8.468300e+02 -6.029399e+02 +10 9879 1.178600e+03 -4.803700e+02 +12 9879 5.950901e+02 -6.564700e+02 +18 9879 7.176299e+02 -1.186899e+02 +20 9879 6.220801e+02 -2.919700e+02 +10 9880 9.555200e+02 -4.798900e+02 +20 9880 4.710900e+02 -2.833500e+02 +10 9881 -2.409301e+02 -4.799800e+02 +12 9881 -8.684200e+02 -6.032100e+02 +10 9882 -2.886899e+02 -4.801400e+02 +12 9882 -9.239000e+02 -6.036200e+02 +10 9883 -1.246180e+03 -4.714399e+02 +15 9883 8.061899e+02 8.726001e+01 +10 9884 1.254960e+03 -4.698600e+02 +18 9884 7.785000e+02 -1.138199e+02 +10 9885 -1.291330e+03 -4.654900e+02 +20 9885 -1.191340e+03 -2.554399e+02 +10 9886 1.456890e+03 -4.643600e+02 +18 9886 9.395300e+02 -1.179399e+02 +20 9886 8.096899e+02 -2.893000e+02 +10 9887 8.936201e+02 -4.639800e+02 +18 9887 5.243101e+02 -6.841003e+01 +20 9887 4.546500e+02 -2.501000e+02 +10 9888 -1.299690e+03 -4.629900e+02 +11 9888 -9.985600e+02 7.820007e+00 +15 9888 7.574200e+02 9.338000e+01 +10 9889 1.509650e+03 -4.623000e+02 +18 9889 9.806899e+02 -1.185400e+02 +20 9889 8.448201e+02 -2.892000e+02 +10 9890 9.782800e+02 -4.609000e+02 +12 9890 4.040800e+02 -6.278700e+02 +17 9890 9.091201e+02 2.048401e+02 +20 9890 4.862700e+02 -2.711400e+02 +10 9891 9.782800e+02 -4.609000e+02 +12 9891 4.040800e+02 -6.278700e+02 +17 9891 9.091201e+02 2.048401e+02 +20 9891 4.862700e+02 -2.711400e+02 +10 9892 6.641499e+02 -4.559600e+02 +12 9892 1.547000e+02 -5.869301e+02 +18 9892 3.192000e+02 -5.669995e+01 +10 9893 -8.618005e+01 -4.354301e+02 +12 9893 -6.697200e+02 -5.342800e+02 +10 9894 -1.214780e+03 -4.287600e+02 +20 9894 -1.138930e+03 -2.244399e+02 +10 9895 7.689299e+02 -4.064200e+02 +18 9895 4.224900e+02 -9.140015e+00 +10 9896 7.689299e+02 -4.064200e+02 +18 9896 4.224900e+02 -9.140015e+00 +20 9896 3.666300e+02 -1.994399e+02 +10 9897 -1.198620e+03 -3.940400e+02 +19 9897 6.545200e+02 2.141200e+02 +10 9898 -2.217600e+02 -3.918700e+02 +12 9898 -8.419900e+02 -5.034500e+02 +20 9898 -3.870000e+02 -1.866400e+02 +10 9899 1.602520e+03 -3.895900e+02 +12 9899 1.003430e+03 -5.796700e+02 +10 9900 -2.259301e+02 -3.851100e+02 +13 9900 -1.703070e+03 5.215701e+02 +18 9900 -4.605699e+02 1.905005e+01 +10 9901 -2.543900e+02 -3.823500e+02 +12 9901 -8.800700e+02 -4.949000e+02 +10 9902 -1.506400e+02 -3.820900e+02 +18 9902 -3.974000e+02 2.709998e+01 +10 9903 -1.506400e+02 -3.820900e+02 +18 9903 -3.974000e+02 2.709998e+01 +10 9904 -3.269000e+02 -3.793900e+02 +12 9904 -9.644600e+02 -4.925699e+02 +10 9905 -1.717400e+02 -3.777800e+02 +12 9905 -7.810300e+02 -4.836000e+02 +10 9906 -1.215601e+02 -3.733101e+02 +13 9906 -1.233030e+03 5.503700e+02 +18 9906 -3.736300e+02 3.845996e+01 +20 9906 -3.157700e+02 -1.641801e+02 +10 9907 4.233301e+02 -3.685699e+02 +12 9907 -1.298700e+02 -4.927900e+02 +13 9907 1.242020e+03 5.133201e+02 +17 9907 -7.144900e+02 4.968000e+02 +18 9907 1.062500e+02 1.992004e+01 +20 9907 9.759998e+01 -1.776500e+02 +10 9908 4.233301e+02 -3.685699e+02 +12 9908 -1.298700e+02 -4.927900e+02 +18 9908 1.062500e+02 1.992004e+01 +20 9908 9.759998e+01 -1.776500e+02 +10 9909 4.392100e+02 -3.681300e+02 +12 9909 -1.109600e+02 -4.929000e+02 +17 9909 -6.690200e+02 4.956300e+02 +20 9909 1.102800e+02 -1.777100e+02 +10 9910 4.392100e+02 -3.681300e+02 +12 9910 -1.109600e+02 -4.929000e+02 +17 9910 -6.690200e+02 4.956300e+02 +18 9910 1.207600e+02 1.982996e+01 +20 9910 1.102800e+02 -1.777100e+02 +10 9911 4.548799e+02 -3.673300e+02 +12 9911 -9.413000e+01 -4.924900e+02 +18 9911 1.345400e+02 1.997998e+01 +20 9911 1.217100e+02 -1.775000e+02 +10 9912 7.158501e+02 -3.664700e+02 +18 9912 3.628500e+02 3.538000e+01 +20 9912 3.325601e+02 -1.615601e+02 +10 9913 6.097400e+02 -3.621300e+02 +20 9913 2.378900e+02 -1.754399e+02 +10 9914 -1.207620e+03 -3.614301e+02 +11 9914 -9.037100e+02 1.477500e+02 +10 9915 5.515200e+02 -3.601300e+02 +12 9915 1.651001e+01 -4.850300e+02 +18 9915 2.196700e+02 2.458997e+01 +10 9916 6.304900e+02 -3.571200e+02 +20 9916 2.534700e+02 -1.718300e+02 +10 9917 -1.283310e+03 -3.534100e+02 +16 9917 -4.359900e+02 3.353900e+02 +10 9918 1.166860e+03 -3.519200e+02 +12 9918 5.890801e+02 -5.241700e+02 +17 9918 1.421220e+03 4.660300e+02 +20 9918 6.187000e+02 -2.011801e+02 +10 9919 8.109800e+02 -3.347400e+02 +18 9919 4.588199e+02 5.004004e+01 +20 9919 3.969600e+02 -1.488500e+02 +10 9920 -1.117280e+03 -3.336300e+02 +16 9920 -1.835400e+02 3.635100e+02 +10 9921 7.043201e+02 -3.330699e+02 +18 9921 3.749600e+02 6.681006e+01 +20 9921 3.243400e+02 -1.354800e+02 +10 9922 7.268999e+02 -3.318400e+02 +18 9922 3.954200e+02 6.678003e+01 +10 9923 -2.079000e+02 -3.107100e+02 +12 9923 -8.230900e+02 -4.119600e+02 +10 9924 6.827500e+02 -2.998500e+02 +12 9924 2.277400e+02 -3.917700e+02 +18 9924 3.566500e+02 9.778003e+01 +10 9925 1.072880e+03 -2.995900e+02 +18 9925 6.432800e+02 3.515002e+01 +10 9926 1.631870e+03 -2.989600e+02 +20 9926 9.332300e+02 -1.795200e+02 +10 9927 6.803799e+02 -2.954500e+02 +12 9927 2.262200e+02 -3.866000e+02 +10 9928 1.050770e+03 -2.947900e+02 +12 9928 4.785699e+02 -4.596500e+02 +17 9928 1.140140e+03 6.220801e+02 +10 9929 7.087700e+02 -2.934800e+02 +20 9929 3.293400e+02 -1.043700e+02 +10 9930 9.649299e+02 -2.911400e+02 +12 9930 3.989500e+02 -4.501600e+02 +17 9930 8.998301e+02 6.419099e+02 +18 9930 5.574900e+02 4.903003e+01 +20 9930 4.828900e+02 -1.495601e+02 +10 9931 -1.112500e+02 -2.861200e+02 +12 9931 -6.784800e+02 -3.479100e+02 +10 9932 1.137890e+03 -2.830900e+02 +12 9932 5.649199e+02 -4.517300e+02 +17 9932 1.365300e+03 6.432800e+02 +20 9932 6.018201e+02 -1.515500e+02 +10 9933 1.030030e+03 -2.821700e+02 +20 9933 5.276400e+02 -1.463500e+02 +10 9934 7.093601e+02 -2.749301e+02 +18 9934 3.822200e+02 1.200901e+02 +10 9935 1.207920e+03 -2.741899e+02 +12 9935 6.331001e+02 -4.456801e+02 +17 9935 1.547370e+03 6.587900e+02 +18 9935 7.547900e+02 4.939001e+01 +20 9935 6.501001e+02 -1.480100e+02 +10 9936 1.219200e+03 -2.733199e+02 +12 9936 6.444299e+02 -4.454800e+02 +18 9936 7.637500e+02 4.947998e+01 +20 9936 6.583101e+02 -1.477700e+02 +10 9937 1.219200e+03 -2.733199e+02 +12 9937 6.444299e+02 -4.454800e+02 +17 9937 1.579570e+03 6.600000e+02 +18 9937 7.637500e+02 4.947998e+01 +20 9937 6.583101e+02 -1.477700e+02 +10 9938 4.082700e+02 -2.734900e+02 +12 9938 -1.081899e+02 -3.685699e+02 +20 9938 9.295996e+01 -9.275000e+01 +10 9939 7.015100e+02 -2.670500e+02 +12 9939 2.508700e+02 -3.555300e+02 +18 9939 3.757600e+02 1.268401e+02 +20 9939 3.244600e+02 -8.369995e+01 +10 9940 9.625901e+02 -2.535601e+02 +17 9940 8.977200e+02 7.354200e+02 +18 9940 5.575100e+02 8.085999e+01 +20 9940 4.824700e+02 -1.232100e+02 +10 9941 -2.191100e+02 -2.522500e+02 +18 9941 -4.528700e+02 1.368101e+02 +20 9941 -3.834800e+02 -8.004004e+01 +10 9942 1.083080e+03 -2.509000e+02 +12 9942 5.138000e+02 -4.160200e+02 +17 9942 1.232500e+03 7.310200e+02 +18 9942 6.548401e+02 7.566992e+01 +20 9942 5.655601e+02 -1.265699e+02 +10 9943 1.023060e+03 -2.465699e+02 +12 9943 4.545300e+02 -4.083101e+02 +10 9944 6.901299e+02 -2.409900e+02 +12 9944 2.407700e+02 -3.242600e+02 +10 9945 -2.337900e+02 -2.410300e+02 +12 9945 -8.514300e+02 -3.363700e+02 +10 9946 9.840000e+02 -2.407600e+02 +17 9946 9.672200e+02 7.706600e+02 +18 9946 5.758799e+02 8.955005e+01 +10 9947 -3.463700e+02 -2.348700e+02 +18 9947 -5.625100e+02 1.494299e+02 +10 9948 4.254600e+02 -2.298600e+02 +20 9948 1.073500e+02 -5.881995e+01 +10 9949 -2.875500e+02 -2.299900e+02 +12 9949 -9.136300e+02 -3.269000e+02 +10 9950 -2.875500e+02 -2.299900e+02 +18 9950 -5.107000e+02 1.537300e+02 +10 9951 9.607300e+02 -2.217700e+02 +12 9951 3.984200e+02 -3.768800e+02 +10 9952 9.867600e+02 -2.179301e+02 +12 9952 4.224301e+02 -3.752200e+02 +17 9952 9.763601e+02 8.286700e+02 +18 9952 5.792300e+02 1.089299e+02 +20 9952 5.005000e+02 -9.847998e+01 +10 9953 4.524299e+02 -2.151000e+02 +12 9953 -5.539001e+01 -3.037200e+02 +20 9953 1.286200e+02 -4.951001e+01 +10 9954 1.022680e+03 -2.142800e+02 +12 9954 4.391100e+02 -3.742000e+02 +10 9955 9.509800e+02 -2.088101e+02 +12 9955 3.937700e+02 -3.617300e+02 +18 9955 5.544199e+02 1.201799e+02 +10 9956 9.303601e+02 -2.083101e+02 +18 9956 5.379399e+02 1.236599e+02 +20 9956 4.649100e+02 -8.625000e+01 +10 9957 1.035090e+03 -2.053600e+02 +12 9957 4.696100e+02 -3.657400e+02 +17 9957 1.110940e+03 8.542400e+02 +10 9958 1.129730e+03 -2.042300e+02 +12 9958 5.615801e+02 -3.692800e+02 +17 9958 1.360220e+03 8.470800e+02 +18 9958 6.961599e+02 1.121899e+02 +20 9958 5.994800e+02 -9.493994e+01 +10 9959 1.077860e+03 -2.017000e+02 +12 9959 5.108101e+02 -3.637600e+02 +17 9959 1.225640e+03 8.592900e+02 +18 9959 6.538701e+02 1.180000e+02 +20 9959 5.638000e+02 -9.083997e+01 +10 9960 9.433401e+02 -2.015601e+02 +12 9960 3.879500e+02 -3.561100e+02 +18 9960 5.470000e+02 1.262600e+02 +20 9960 4.727300e+02 -8.367004e+01 +10 9961 1.125410e+03 -1.995601e+02 +12 9961 5.577100e+02 -3.646100e+02 +17 9961 1.350260e+03 8.604399e+02 +18 9961 6.930000e+02 1.162400e+02 +20 9961 5.967100e+02 -9.107996e+01 +10 9962 -4.600900e+02 -1.980699e+02 +16 9962 2.361600e+02 4.980000e+02 +10 9963 1.154530e+03 -1.971600e+02 +12 9963 5.863601e+02 -3.634500e+02 +18 9963 7.169900e+02 1.165300e+02 +20 9963 6.170300e+02 -9.084998e+01 +10 9964 9.795000e+02 -1.957100e+02 +12 9964 4.167100e+02 -3.515699e+02 +17 9964 9.584399e+02 8.865500e+02 +18 9964 5.743899e+02 1.282800e+02 +20 9964 4.958800e+02 -8.193005e+01 +10 9965 1.150560e+03 -1.951300e+02 +12 9965 5.822700e+02 -3.608000e+02 +17 9965 1.417410e+03 8.655900e+02 +18 9965 7.135801e+02 1.196200e+02 +20 9965 6.143799e+02 -8.931006e+01 +10 9966 9.422700e+02 -1.919301e+02 +18 9966 5.456699e+02 1.349399e+02 +10 9967 -9.616300e+02 -1.913900e+02 +16 9967 -9.571002e+01 4.796700e+02 +10 9968 1.089530e+03 -1.854301e+02 +17 9968 1.257170e+03 9.017200e+02 +18 9968 6.651299e+02 1.301599e+02 +10 9969 9.380400e+02 -1.852800e+02 +17 9969 8.341001e+02 9.198101e+02 +10 9970 -1.285240e+03 -1.596200e+02 +11 9970 -1.011420e+03 4.099100e+02 +16 9970 -4.507800e+02 4.813900e+02 +10 9971 1.858199e+02 -1.491100e+02 +16 9971 4.081400e+02 5.688300e+02 +10 9972 -4.828101e+02 -1.441700e+02 +12 9972 -1.129170e+03 -2.153500e+02 +10 9973 9.711399e+02 -1.385200e+02 +12 9973 4.146600e+02 -2.890400e+02 +10 9974 1.942100e+02 -1.359900e+02 +18 9974 -8.838000e+01 1.316300e+02 +10 9975 2.268400e+02 -1.288900e+02 +20 9975 -4.356995e+01 -8.256006e+01 +10 9976 2.268400e+02 -1.288900e+02 +18 9976 -6.434998e+01 1.336400e+02 +10 9977 1.535840e+03 -1.064900e+02 +12 9977 9.578501e+02 -2.887700e+02 +18 9977 1.031950e+03 1.722300e+02 +10 9978 -1.363980e+03 1.153300e+02 +20 9978 -1.255860e+03 1.893700e+02 +10 9979 -1.363980e+03 1.153300e+02 +16 9979 -5.329900e+02 6.880300e+02 +10 9980 -1.559570e+03 1.426300e+02 +15 9980 5.312100e+02 5.410601e+02 +19 9980 1.243000e+02 8.642500e+02 +10 9981 -1.250410e+03 1.545000e+02 +15 9981 -1.990800e+02 4.568201e+02 +10 9982 -1.399280e+03 1.601400e+02 +14 9982 -1.455500e+02 5.629000e+02 +10 9983 3.017600e+02 9.018701e+02 +20 9983 3.351001e+01 6.249900e+02 +10 9984 1.969000e+02 9.920601e+02 +12 9984 -4.412700e+02 7.765701e+02 +10 9985 1.848900e+02 9.978799e+02 +12 9985 -4.510300e+02 7.867900e+02 +10 9986 1.771700e+02 1.013950e+03 +20 9986 -4.843005e+01 7.236600e+02 +10 9987 2.234100e+02 1.042620e+03 +20 9987 -1.520996e+01 7.435300e+02 +10 9988 2.203000e+02 1.080650e+03 +20 9988 -1.694995e+01 7.720000e+02 +10 9989 -1.570100e+02 -7.170699e+02 +12 9989 -9.158600e+02 -9.285699e+02 +10 9990 -1.571700e+02 -7.109900e+02 +12 9990 -9.157500e+02 -9.225000e+02 +10 9991 -1.467000e+02 -6.911100e+02 +12 9991 -8.764100e+02 -8.909600e+02 +10 9992 -5.639001e+01 -6.845800e+02 +12 9992 -7.880800e+02 -8.834100e+02 +10 9993 -1.362700e+02 -6.355400e+02 +12 9993 -8.639800e+02 -8.396300e+02 +10 9994 -1.170699e+02 -6.049700e+02 +12 9994 -8.441700e+02 -8.104900e+02 +10 9995 -2.481000e+02 -5.756500e+02 +12 9995 -8.807500e+02 -7.090000e+02 +10 9996 -2.674600e+02 -5.749500e+02 +12 9996 -9.029200e+02 -7.092400e+02 +10 9997 -2.204600e+02 -5.525900e+02 +12 9997 -8.470900e+02 -6.826899e+02 +10 9998 -2.289700e+02 -5.461000e+02 +12 9998 -8.571800e+02 -6.761300e+02 +10 9999 -2.306700e+02 -5.277500e+02 +18 9999 -4.661801e+02 -1.053800e+02 +10 10000 -2.397100e+02 -5.208600e+02 +12 10000 -8.689500e+02 -6.480000e+02 +10 10001 -2.397100e+02 -5.208600e+02 +12 10001 -8.689500e+02 -6.480000e+02 +18 10001 -4.730800e+02 -9.943994e+01 +10 10002 5.413401e+02 -4.964200e+02 +18 10002 2.055100e+02 -9.389001e+01 +20 10002 1.834399e+02 -2.748500e+02 +10 10003 -1.355200e+02 -4.879700e+02 +12 10003 -7.397300e+02 -6.037300e+02 +10 10004 -1.220530e+03 -4.822600e+02 +11 10004 -9.093300e+02 -1.170001e+01 +10 10005 -1.243560e+03 -4.822200e+02 +11 10005 -9.335300e+02 -1.301001e+01 +15 10005 8.090601e+02 7.851001e+01 +10 10006 -1.358600e+02 -4.790800e+02 +12 10006 -7.396800e+02 -5.923300e+02 +10 10007 8.884199e+02 -4.761600e+02 +18 10007 5.192100e+02 -7.883997e+01 +20 10007 4.507900e+02 -2.590500e+02 +10 10008 1.057690e+03 -4.750200e+02 +12 10008 4.780200e+02 -6.463300e+02 +10 10009 1.328400e+03 -4.703101e+02 +20 10009 7.239399e+02 -2.894800e+02 +10 10010 -1.215130e+03 -4.685300e+02 +15 10010 8.366899e+02 8.969000e+01 +10 10011 1.442250e+03 -4.653900e+02 +18 10011 9.275500e+02 -1.182000e+02 +10 10012 8.488899e+02 -4.657200e+02 +20 10012 4.223199e+02 -2.496700e+02 +10 10013 -9.023999e+01 -4.636300e+02 +12 10013 -6.758400e+02 -5.671500e+02 +10 10014 -1.281380e+03 -4.621500e+02 +11 10014 -9.762200e+02 1.013000e+01 +10 10015 1.007370e+03 -4.597100e+02 +20 10015 5.061300e+02 -2.715900e+02 +10 10016 9.761499e+02 -4.578000e+02 +12 10016 4.010100e+02 -6.230900e+02 +20 10016 4.853199e+02 -2.684500e+02 +10 10017 -2.542600e+02 -4.564900e+02 +12 10017 -8.822700e+02 -5.767600e+02 +10 10018 1.016610e+03 -4.558800e+02 +12 10018 4.404301e+02 -6.246700e+02 +18 10018 5.894600e+02 -9.080005e+01 +20 10018 5.125100e+02 -2.690100e+02 +10 10019 -2.857500e+02 -4.517800e+02 +12 10019 -9.196900e+02 -5.724600e+02 +10 10020 5.205701e+02 -4.510400e+02 +12 10020 -2.092004e+01 -5.838000e+02 +17 10020 -4.815699e+02 2.655100e+02 +20 10020 1.691400e+02 -2.397700e+02 +10 10021 5.720200e+02 -4.483900e+02 +12 10021 3.518005e+01 -5.822500e+02 +10 10022 6.317600e+02 -4.470699e+02 +18 10022 2.859100e+02 -5.312000e+01 +10 10023 4.637000e+02 -4.329200e+02 +12 10023 -8.606995e+01 -5.640300e+02 +13 10023 1.419520e+03 2.179500e+02 +10 10024 -1.893500e+02 -4.265100e+02 +18 10024 -4.308500e+02 -1.434998e+01 +10 10025 -1.973500e+02 -4.229900e+02 +12 10025 -8.136400e+02 -5.359301e+02 +10 10026 1.161970e+03 -4.223000e+02 +12 10026 5.818701e+02 -5.961600e+02 +17 10026 1.399780e+03 2.869700e+02 +18 10026 7.078301e+02 -7.028003e+01 +10 10027 -6.288000e+01 -4.196500e+02 +12 10027 -6.338000e+02 -5.109600e+02 +13 10027 -9.817600e+02 3.053401e+02 +18 10027 -3.273000e+02 7.640015e+00 +20 10027 -2.768400e+02 -1.902900e+02 +10 10028 -6.288000e+01 -4.196500e+02 +12 10028 -6.338000e+02 -5.109600e+02 +18 10028 -3.273000e+02 7.640015e+00 +20 10028 -2.768400e+02 -1.902900e+02 +10 10029 -1.214190e+03 -4.132200e+02 +20 10029 -1.138740e+03 -2.125500e+02 +10 10030 -1.213810e+03 -4.052500e+02 +15 10030 8.362400e+02 1.410600e+02 +20 10030 -1.138570e+03 -2.065100e+02 +10 10031 -7.584998e+01 -4.034399e+02 +12 10031 -6.500200e+02 -4.924700e+02 +10 10032 9.291001e+02 -4.016600e+02 +17 10032 4.229900e+02 3.544500e+02 +10 10033 7.533701e+02 -3.967300e+02 +18 10033 4.103400e+02 1.819946e+00 +10 10034 7.567400e+02 -3.889700e+02 +18 10034 4.135699e+02 8.760010e+00 +20 10034 3.587000e+02 -1.849500e+02 +10 10035 -2.456500e+02 -3.887900e+02 +12 10035 -8.706400e+02 -5.014900e+02 +10 10036 -1.899900e+02 -3.868199e+02 +12 10036 -8.034900e+02 -4.946801e+02 +13 10036 -1.539430e+03 5.081599e+02 +10 10037 -1.465200e+02 -3.853101e+02 +12 10037 -7.497500e+02 -4.877300e+02 +10 10038 7.119500e+02 -3.835601e+02 +18 10038 3.770800e+02 2.031995e+01 +10 10039 -3.355500e+02 -3.803800e+02 +12 10039 -9.730700e+02 -4.935200e+02 +10 10040 7.082400e+02 -3.758900e+02 +18 10040 3.758500e+02 2.729004e+01 +10 10041 7.082400e+02 -3.758900e+02 +18 10041 3.758500e+02 2.729004e+01 +10 10042 6.788701e+02 -3.757100e+02 +18 10042 3.355200e+02 1.314001e+01 +20 10042 2.926899e+02 -1.815100e+02 +10 10043 7.079900e+02 -3.687100e+02 +18 10043 3.763900e+02 3.391003e+01 +10 10044 -1.211410e+03 -3.661700e+02 +11 10044 -9.079400e+02 1.404400e+02 +20 10044 -1.136810e+03 -1.768199e+02 +10 10045 1.648890e+03 -3.651000e+02 +12 10045 1.048430e+03 -5.563600e+02 +10 10046 6.262600e+02 -3.651500e+02 +12 10046 9.705005e+01 -4.929100e+02 +18 10046 2.838800e+02 1.813000e+01 +20 10046 2.498800e+02 -1.779000e+02 +10 10047 7.080300e+02 -3.611500e+02 +18 10047 3.767300e+02 4.090002e+01 +10 10048 7.080300e+02 -3.611500e+02 +18 10048 3.767300e+02 4.090002e+01 +10 10049 1.170720e+03 -3.590300e+02 +12 10049 5.934600e+02 -5.316899e+02 +17 10049 1.434350e+03 4.457900e+02 +18 10049 7.191001e+02 -1.873999e+01 +20 10049 6.216899e+02 -2.063800e+02 +10 10050 -1.258390e+03 -3.580000e+02 +19 10050 5.565100e+02 2.612100e+02 +10 10051 9.109500e+02 -3.537700e+02 +17 10051 3.844099e+02 4.784000e+02 +10 10052 8.766001e+02 -3.523700e+02 +18 10052 5.159301e+02 3.092004e+01 +10 10053 -1.721300e+02 -3.373500e+02 +20 10053 -3.508199e+02 -1.415100e+02 +10 10054 6.826699e+02 -3.328199e+02 +12 10054 2.267100e+02 -4.292400e+02 +18 10054 3.550100e+02 6.768994e+01 +10 10055 4.988301e+02 -3.326700e+02 +12 10055 -3.918994e+01 -4.532700e+02 +10 10056 -2.335100e+02 -3.318500e+02 +12 10056 -8.553200e+02 -4.375400e+02 +10 10057 -1.963300e+02 -3.091400e+02 +18 10057 -4.351899e+02 8.891992e+01 +10 10058 -1.341200e+02 -3.043600e+02 +12 10058 -7.308900e+02 -3.965601e+02 +10 10059 1.055620e+03 -3.036400e+02 +12 10059 4.825500e+02 -4.690900e+02 +17 10059 1.150730e+03 5.992000e+02 +10 10060 6.847300e+02 -3.036600e+02 +12 10060 2.299301e+02 -3.960500e+02 +18 10060 3.582200e+02 9.403003e+01 +20 10060 3.100601e+02 -1.117100e+02 +10 10061 9.469800e+02 -3.025400e+02 +18 10061 5.425000e+02 4.058997e+01 +10 10062 1.081090e+03 -2.994900e+02 +12 10062 5.078400e+02 -4.662600e+02 +17 10062 1.217470e+03 6.071300e+02 +18 10062 6.495701e+02 3.506006e+01 +10 10063 -1.191620e+03 -2.990500e+02 +16 10063 -3.584100e+02 3.813400e+02 +10 10064 1.101990e+03 -2.980400e+02 +12 10064 5.282500e+02 -4.659399e+02 +17 10064 1.272100e+03 6.082600e+02 +18 10064 6.670200e+02 3.502002e+01 +10 10065 1.119620e+03 -2.970800e+02 +12 10065 5.457400e+02 -4.656100e+02 +17 10065 1.320620e+03 6.093201e+02 +18 10065 6.813999e+02 3.497998e+01 +10 10066 1.139580e+03 -2.954600e+02 +12 10066 5.654700e+02 -4.648900e+02 +17 10066 1.370330e+03 6.112900e+02 +18 10066 6.982000e+02 3.559998e+01 +20 10066 6.027100e+02 -1.604399e+02 +10 10067 1.005860e+03 -2.955900e+02 +17 10067 1.020010e+03 6.241400e+02 +10 10068 1.160390e+03 -2.936200e+02 +17 10068 1.424070e+03 6.127900e+02 +18 10068 7.148000e+02 3.557996e+01 +10 10069 1.173800e+03 -2.931500e+02 +12 10069 5.991299e+02 -4.640500e+02 +10 10070 1.534730e+03 -2.852300e+02 +12 10070 9.454099e+02 -4.714600e+02 +18 10070 1.015210e+03 2.435999e+01 +10 10071 6.393301e+02 -2.842200e+02 +12 10071 1.398900e+02 -3.930400e+02 +10 10072 6.393301e+02 -2.842200e+02 +12 10072 1.398900e+02 -3.930400e+02 +10 10073 1.561860e+03 -2.810100e+02 +12 10073 9.716399e+02 -4.683900e+02 +20 10073 8.895300e+02 -1.648600e+02 +10 10074 1.644480e+03 -2.763000e+02 +12 10074 1.049070e+03 -4.666801e+02 +20 10074 9.423799e+02 -1.641899e+02 +10 10075 7.160100e+02 -2.745300e+02 +12 10075 2.669200e+02 -3.636899e+02 +18 10075 3.885400e+02 1.194000e+02 +20 10075 3.353101e+02 -8.996997e+01 +10 10076 6.990500e+02 -2.708300e+02 +12 10076 2.479900e+02 -3.590699e+02 +10 10077 -1.237460e+03 -2.709900e+02 +15 10077 8.076600e+02 2.477300e+02 +10 10078 -2.913700e+02 -2.339600e+02 +12 10078 -9.180300e+02 -3.305300e+02 +10 10079 -2.364700e+02 -2.237300e+02 +12 10079 -8.538000e+02 -3.178700e+02 +10 10080 -2.398199e+02 -2.242400e+02 +18 10080 -4.703300e+02 1.608900e+02 +10 10081 9.648301e+02 -2.213500e+02 +12 10081 4.018800e+02 -3.767400e+02 +20 10081 4.851600e+02 -9.941003e+01 +10 10082 1.815300e+02 -2.193199e+02 +12 10082 -5.323100e+02 -4.420300e+02 +10 10083 1.010060e+03 -2.153000e+02 +12 10083 4.509500e+02 -3.738300e+02 +17 10083 9.927200e+02 8.301799e+02 +20 10083 5.209700e+02 -9.739001e+01 +10 10084 1.016330e+03 -2.149600e+02 +12 10084 4.449200e+02 -3.738800e+02 +18 10084 5.933999e+02 1.096500e+02 +10 10085 1.016330e+03 -2.149600e+02 +12 10085 4.571600e+02 -3.736899e+02 +10 10086 9.947900e+02 -2.128600e+02 +12 10086 4.303300e+02 -3.704500e+02 +10 10087 9.891499e+02 -2.131801e+02 +12 10087 4.249700e+02 -3.707500e+02 +17 10087 9.841299e+02 8.411100e+02 +18 10087 5.815601e+02 1.126300e+02 +10 10088 1.000630e+03 -2.116200e+02 +12 10088 4.416600e+02 -3.692600e+02 +18 10088 5.907800e+02 1.134900e+02 +20 10088 5.143600e+02 -9.402002e+01 +10 10089 1.006540e+03 -2.108000e+02 +17 10089 1.032330e+03 8.454399e+02 +10 10090 1.012620e+03 -2.105500e+02 +12 10090 4.474100e+02 -3.694399e+02 +17 10090 1.049150e+03 8.455000e+02 +20 10090 5.274100e+02 -9.389001e+01 +10 10091 1.012620e+03 -2.105500e+02 +12 10091 4.474100e+02 -3.694399e+02 +17 10091 1.049150e+03 8.455000e+02 +20 10091 5.274100e+02 -9.389001e+01 +10 10092 1.096710e+03 -2.098101e+02 +18 10092 6.690200e+02 1.092300e+02 +20 10092 5.764800e+02 -9.759998e+01 +10 10093 4.438999e+02 -2.096100e+02 +18 10093 1.381200e+02 1.756000e+02 +10 10094 1.018960e+03 -2.092500e+02 +12 10094 4.537600e+02 -3.683300e+02 +17 10094 1.066530e+03 8.480400e+02 +10 10095 1.126070e+03 -2.072300e+02 +17 10095 1.350190e+03 8.411600e+02 +18 10095 6.928999e+02 1.097300e+02 +20 10095 5.968501e+02 -9.665002e+01 +10 10096 1.028480e+03 -2.069200e+02 +12 10096 4.631500e+02 -3.665800e+02 +17 10096 1.092270e+03 8.539100e+02 +10 10097 1.022110e+03 -2.068600e+02 +17 10097 1.092270e+03 8.539100e+02 +10 10098 1.022110e+03 -2.068600e+02 +12 10098 4.569600e+02 -3.667700e+02 +10 10099 1.155230e+03 -2.047500e+02 +20 10099 6.171101e+02 -9.653003e+01 +10 10100 1.081640e+03 -2.032700e+02 +12 10100 5.146600e+02 -3.661400e+02 +17 10100 1.235540e+03 8.550701e+02 +18 10100 6.572100e+02 1.152100e+02 +20 10100 5.663999e+02 -9.231006e+01 +10 10101 1.088920e+03 -2.027600e+02 +12 10101 5.218600e+02 -3.659800e+02 +17 10101 1.254540e+03 8.560601e+02 +10 10102 1.088920e+03 -2.027600e+02 +12 10102 5.218600e+02 -3.659800e+02 +10 10103 1.184840e+03 -2.021899e+02 +12 10103 5.937400e+02 -3.711801e+02 +20 10103 6.377200e+02 -9.555005e+01 +10 10104 1.085160e+03 -2.018101e+02 +12 10104 5.182000e+02 -3.644399e+02 +17 10104 1.340540e+03 8.647000e+02 +18 10104 6.601399e+02 1.168600e+02 +10 10105 1.092300e+03 -2.009900e+02 +12 10105 5.254301e+02 -3.642100e+02 +18 10105 6.660200e+02 1.172200e+02 +10 10106 1.106910e+03 -1.992200e+02 +12 10106 5.395601e+02 -3.631700e+02 +10 10107 -3.490800e+02 -1.910900e+02 +18 10107 -5.647000e+02 1.884000e+02 +10 10108 -1.232260e+03 -1.855100e+02 +20 10108 -1.152820e+03 -3.981995e+01 +10 10109 -8.004900e+02 -1.711600e+02 +16 10109 1.737000e+01 5.041700e+02 +19 10109 1.372440e+03 5.282100e+02 +10 10110 -5.638400e+02 -1.675100e+02 +12 10110 -1.224600e+03 -2.419500e+02 +10 10111 2.174900e+02 -1.657100e+02 +12 10111 -4.915400e+02 -3.879301e+02 +18 10111 -7.264001e+01 1.044500e+02 +10 10112 2.205800e+02 -1.574900e+02 +12 10112 -4.877800e+02 -3.794600e+02 +10 10113 1.161020e+03 -1.557100e+02 +12 10113 5.964500e+02 -3.201600e+02 +10 10114 -5.248300e+02 -1.515601e+02 +12 10114 -1.177560e+03 -2.235400e+02 +10 10115 9.866101e+02 -1.453101e+02 +12 10115 4.301200e+02 -2.965900e+02 +17 10115 9.739399e+02 1.023210e+03 +20 10115 5.044399e+02 -4.430005e+01 +10 10116 2.698000e+02 -1.389800e+02 +16 10116 4.630500e+02 5.798700e+02 +10 10117 1.079230e+03 -1.371000e+02 +12 10117 5.257800e+02 -2.899000e+02 +20 10117 5.710400e+02 -4.064001e+01 +10 10118 1.569160e+03 -1.135900e+02 +12 10118 9.883000e+02 -2.977900e+02 +10 10119 -8.560800e+02 -1.108700e+02 +16 10119 -1.359998e+01 5.503300e+02 +19 10119 1.313630e+03 5.948700e+02 +10 10120 1.548220e+03 -1.052800e+02 +12 10120 9.691799e+02 -2.884100e+02 +18 10120 1.041340e+03 1.726699e+02 +10 10121 1.548740e+03 -1.020000e+02 +12 10121 9.694399e+02 -2.848900e+02 +18 10121 1.041390e+03 1.758500e+02 +10 10122 1.266030e+03 -7.831995e+01 +12 10122 7.053201e+02 -2.443600e+02 +10 10123 1.474240e+03 -4.289001e+01 +12 10123 9.080200e+02 -2.190000e+02 +10 10124 1.514350e+03 -3.356006e+01 +12 10124 9.400000e+02 -2.141100e+02 +10 10125 -1.364670e+03 9.969971e+00 +15 10125 6.804000e+02 4.608101e+02 +16 10125 -5.279600e+02 6.050400e+02 +10 10126 -1.199040e+03 1.966003e+01 +11 10126 -9.357300e+02 6.661300e+02 +10 10127 -1.316380e+03 3.607996e+01 +20 10127 -1.216940e+03 1.287600e+02 +10 10128 -1.350380e+03 4.113000e+01 +20 10128 -1.242040e+03 1.310300e+02 +10 10129 -1.382690e+03 4.809998e+01 +20 10129 -1.266650e+03 1.361100e+02 +10 10130 -1.422590e+03 5.672998e+01 +15 10130 6.331400e+02 4.909500e+02 +10 10131 -1.250850e+03 1.104000e+02 +20 10131 -1.169920e+03 1.899800e+02 +10 10132 -1.250850e+03 1.104000e+02 +20 10132 -1.169920e+03 1.899800e+02 +10 10133 -1.370090e+03 1.319500e+02 +20 10133 -1.262570e+03 2.044199e+02 +10 10134 1.420300e+02 8.126799e+02 +12 10134 -4.999400e+02 6.074500e+02 +10 10135 1.934800e+02 9.676299e+02 +12 10135 -4.460500e+02 7.520500e+02 +10 10136 1.722400e+02 1.008790e+03 +20 10136 -5.207996e+01 7.203900e+02 +10 10137 -5.947998e+01 -6.867200e+02 +12 10137 -7.910900e+02 -8.857800e+02 +10 10138 -1.285300e+02 -6.689700e+02 +12 10138 -8.579000e+02 -8.704100e+02 +10 10139 -1.421500e+02 -6.370200e+02 +12 10139 -8.698300e+02 -8.410601e+02 +10 10140 -1.437800e+02 -6.346801e+02 +12 10140 -8.704300e+02 -8.385601e+02 +10 10141 -1.425699e+02 -6.316801e+02 +12 10141 -8.699100e+02 -8.356300e+02 +10 10142 -1.484100e+02 -6.290699e+02 +12 10142 -8.753900e+02 -8.338000e+02 +10 10143 -1.368300e+02 -6.217600e+02 +12 10143 -8.633400e+02 -8.268700e+02 +10 10144 -1.397200e+02 -6.205300e+02 +12 10144 -8.664700e+02 -8.251400e+02 +10 10145 -1.341801e+02 -6.196700e+02 +12 10145 -8.611100e+02 -8.245100e+02 +10 10146 -1.374200e+02 -5.838101e+02 +12 10146 -8.629100e+02 -7.913800e+02 +10 10147 -2.259000e+02 -5.668000e+02 +12 10147 -8.542000e+02 -6.990699e+02 +10 10148 -6.083997e+01 -5.451700e+02 +12 10148 -7.452600e+02 -7.269301e+02 +10 10149 -2.265200e+02 -5.431400e+02 +12 10149 -8.540900e+02 -6.720800e+02 +10 10150 -2.162500e+02 -5.407500e+02 +12 10150 -8.419900e+02 -6.696200e+02 +10 10151 -2.162500e+02 -5.407500e+02 +12 10151 -8.419900e+02 -6.696200e+02 +10 10152 1.075520e+03 -5.253400e+02 +20 10152 5.498000e+02 -3.201801e+02 +10 10153 5.979500e+02 -5.243300e+02 +12 10153 -1.006300e+02 -7.205200e+02 +10 10154 6.055601e+02 -5.220500e+02 +12 10154 -9.256995e+01 -7.175100e+02 +10 10155 5.543401e+02 -5.183500e+02 +20 10155 1.914700e+02 -2.917300e+02 +10 10156 6.361599e+02 -5.176500e+02 +12 10156 1.023700e+02 -6.594700e+02 +10 10157 4.654099e+02 -5.168900e+02 +12 10157 -8.803003e+01 -6.562400e+02 +10 10158 6.353101e+02 -5.060601e+02 +12 10158 1.021801e+02 -6.470100e+02 +18 10158 2.864700e+02 -1.041600e+02 +10 10159 7.027900e+02 -5.052400e+02 +12 10159 1.940601e+02 -6.413101e+02 +10 10160 6.826399e+02 -4.949100e+02 +18 10160 3.332000e+02 -9.130005e+01 +10 10161 6.826399e+02 -4.949100e+02 +18 10161 3.332000e+02 -9.130005e+01 +10 10162 -3.018300e+02 -4.840400e+02 +12 10162 -9.394400e+02 -6.083400e+02 +10 10163 -1.062700e+02 -4.815100e+02 +12 10163 -7.000200e+02 -5.914600e+02 +10 10164 1.095540e+03 -4.756300e+02 +12 10164 5.152200e+02 -6.489600e+02 +10 10165 -1.663900e+02 -4.624700e+02 +12 10165 -7.779000e+02 -5.782700e+02 +10 10166 9.650801e+02 -4.615699e+02 +12 10166 3.922300e+02 -6.275200e+02 +10 10167 1.037860e+03 -4.553400e+02 +12 10167 4.607600e+02 -6.251500e+02 +17 10167 1.072630e+03 2.142300e+02 +18 10167 6.058601e+02 -9.129004e+01 +10 10168 4.116599e+02 -4.525800e+02 +12 10168 -1.432800e+02 -5.845200e+02 +10 10169 1.206590e+03 -4.484301e+02 +17 10169 1.331670e+03 2.158600e+02 +10 10170 7.492800e+02 -4.461000e+02 +18 10170 4.048000e+02 -4.155005e+01 +10 10171 4.588999e+02 -4.457000e+02 +12 10171 -9.189001e+01 -5.778800e+02 +10 10172 6.285400e+02 -4.441600e+02 +12 10172 9.602002e+01 -5.793000e+02 +10 10173 -1.260000e+02 -4.432300e+02 +12 10173 -7.242600e+02 -5.507500e+02 +10 10174 -2.318300e+02 -4.367500e+02 +12 10174 -8.566300e+02 -5.547100e+02 +10 10175 -2.412500e+02 -4.359200e+02 +12 10175 -8.675300e+02 -5.537000e+02 +10 10176 1.160650e+03 -4.252200e+02 +12 10176 5.804500e+02 -5.996100e+02 +17 10176 1.395860e+03 2.796599e+02 +18 10176 7.063501e+02 -7.281995e+01 +10 10177 1.160360e+03 -4.163700e+02 +12 10177 5.778601e+02 -5.896500e+02 +17 10177 1.396780e+03 3.021200e+02 +18 10177 7.052500e+02 -6.490002e+01 +20 10177 6.104700e+02 -2.456200e+02 +10 10178 6.632400e+02 -4.145800e+02 +18 10178 3.199301e+02 -2.066003e+01 +10 10179 5.578101e+02 -4.092300e+02 +12 10179 2.243005e+01 -5.387800e+02 +18 10179 2.232700e+02 -1.803003e+01 +10 10180 -3.330800e+02 -4.079500e+02 +12 10180 -9.720200e+02 -5.239700e+02 +10 10181 6.629199e+02 -4.033000e+02 +20 10181 2.799100e+02 -2.009100e+02 +10 10182 -2.153700e+02 -3.993900e+02 +12 10182 -8.350700e+02 -5.121801e+02 +10 10183 -1.244880e+03 -3.658500e+02 +15 10183 8.044700e+02 1.712600e+02 +10 10184 1.008040e+03 -3.591500e+02 +12 10184 4.344500e+02 -5.238900e+02 +10 10185 5.312300e+02 -3.573800e+02 +12 10185 -6.189941e+00 -4.814900e+02 +17 10185 -4.461500e+02 5.133201e+02 +10 10186 5.640701e+02 -3.563900e+02 +18 10186 2.309600e+02 2.756995e+01 +10 10187 5.532900e+02 -3.566899e+02 +18 10187 2.207800e+02 2.759998e+01 +10 10188 5.364500e+02 -3.548600e+02 +12 10188 -6.500244e-01 -4.783400e+02 +10 10189 5.406799e+02 -3.545400e+02 +12 10189 5.140015e+00 -4.786300e+02 +10 10190 5.406799e+02 -3.545400e+02 +12 10190 5.140015e+00 -4.786300e+02 +10 10191 -2.103101e+02 -3.537700e+02 +12 10191 -8.273200e+02 -4.596200e+02 +10 10192 8.493201e+02 -3.422900e+02 +18 10192 4.920400e+02 4.092004e+01 +10 10193 5.753301e+02 -3.395400e+02 +12 10193 4.350000e+01 -4.634000e+02 +20 10193 2.123700e+02 -1.580000e+02 +10 10194 -2.293300e+02 -3.397800e+02 +12 10194 -8.501700e+02 -4.463199e+02 +10 10195 -2.484100e+02 -3.305900e+02 +12 10195 -8.724000e+02 -4.371400e+02 +10 10196 -2.447100e+02 -3.257900e+02 +12 10196 -8.680100e+02 -4.317700e+02 +10 10197 3.875100e+02 -3.247300e+02 +12 10197 -1.648800e+02 -4.431100e+02 +10 10198 1.071620e+03 -3.169000e+02 +17 10198 1.191640e+03 5.627900e+02 +10 10199 1.071620e+03 -3.169000e+02 +12 10199 4.985500e+02 -4.837200e+02 +17 10199 1.191640e+03 5.627900e+02 +10 10200 3.862500e+02 -3.142100e+02 +18 10200 7.695996e+01 6.838000e+01 +10 10201 4.673501e+02 -3.112100e+02 +17 10201 -5.897200e+02 6.469399e+02 +10 10202 -2.209800e+02 -3.098400e+02 +12 10202 -8.385700e+02 -4.135699e+02 +10 10203 -9.931300e+02 -3.083700e+02 +19 10203 1.131140e+03 3.017600e+02 +10 10204 6.816399e+02 -3.074600e+02 +12 10204 2.262700e+02 -4.004800e+02 +10 10205 -2.374100e+02 -3.073700e+02 +12 10205 -8.586400e+02 -4.114100e+02 +10 10206 4.566001e+02 -3.053500e+02 +12 10206 -8.902002e+01 -4.243700e+02 +10 10207 1.058440e+03 -3.010900e+02 +12 10207 4.869000e+02 -4.667800e+02 +17 10207 1.159280e+03 6.042600e+02 +10 10208 1.066760e+03 -3.004200e+02 +12 10208 4.941200e+02 -4.665100e+02 +10 10209 1.066760e+03 -3.004200e+02 +18 10209 6.378899e+02 3.487000e+01 +10 10210 1.072260e+03 -2.998600e+02 +12 10210 4.999700e+02 -4.663000e+02 +17 10210 1.195030e+03 6.059000e+02 +10 10211 1.128170e+03 -2.961200e+02 +12 10211 5.544900e+02 -4.651200e+02 +17 10211 1.340910e+03 6.101599e+02 +10 10212 1.154420e+03 -2.942800e+02 +12 10212 5.799099e+02 -4.643900e+02 +17 10212 1.410220e+03 6.121799e+02 +10 10213 1.167300e+03 -2.934500e+02 +17 10213 1.441940e+03 6.131400e+02 +18 10213 7.199900e+02 3.563000e+01 +10 10214 -2.383000e+02 -2.930400e+02 +12 10214 -8.590700e+02 -3.952400e+02 +10 10215 4.401899e+02 -2.915900e+02 +17 10215 -6.647400e+02 7.047800e+02 +10 10216 -2.361801e+02 -2.909500e+02 +12 10216 -8.564800e+02 -3.928800e+02 +10 10217 1.535430e+03 -2.820200e+02 +12 10217 9.469800e+02 -4.682900e+02 +18 10217 1.016170e+03 2.707996e+01 +10 10218 -1.655601e+02 -2.646100e+02 +12 10218 -7.607900e+02 -3.456899e+02 +10 10219 -2.389100e+02 -2.592900e+02 +12 10219 -8.579500e+02 -3.574200e+02 +10 10220 -2.733199e+02 -2.354700e+02 +12 10220 -8.972900e+02 -3.320800e+02 +10 10221 1.035020e+03 -2.317800e+02 +17 10221 1.110560e+03 7.875500e+02 +10 10222 -3.765000e+02 -2.304500e+02 +12 10222 -1.014680e+03 -3.262700e+02 +10 10223 4.493999e+02 -2.255500e+02 +12 10223 -5.925000e+01 -3.157800e+02 +13 10223 1.378250e+03 1.134090e+03 +17 10223 -8.014000e+02 8.806599e+02 +18 10223 1.420800e+02 1.609900e+02 +10 10224 4.617000e+02 -2.243600e+02 +12 10224 -4.514001e+01 -3.142600e+02 +10 10225 -2.930400e+02 -2.233600e+02 +12 10225 -9.199800e+02 -3.186000e+02 +18 10225 -5.157600e+02 1.600701e+02 +10 10226 9.888601e+02 -2.213400e+02 +18 10226 5.808601e+02 1.060701e+02 +10 10227 9.663201e+02 -2.168800e+02 +12 10227 4.038000e+02 -3.723500e+02 +10 10228 1.032270e+03 -2.157400e+02 +12 10228 4.663101e+02 -3.764301e+02 +17 10228 1.100770e+03 8.292000e+02 +10 10229 1.032270e+03 -2.157400e+02 +12 10229 4.663101e+02 -3.764301e+02 +17 10229 1.100770e+03 8.292000e+02 +10 10230 1.076180e+03 -2.118101e+02 +17 10230 1.221170e+03 8.341799e+02 +10 10231 9.865801e+02 -2.114500e+02 +18 10231 5.791899e+02 1.150200e+02 +10 10232 1.015730e+03 -2.079800e+02 +12 10232 4.448101e+02 -3.677600e+02 +17 10232 1.008080e+03 8.477700e+02 +10 10233 1.015730e+03 -2.079800e+02 +12 10233 4.507200e+02 -3.671400e+02 +17 10233 9.921899e+02 8.467000e+02 +10 10234 4.269500e+02 -1.977300e+02 +12 10234 -8.272998e+01 -2.830000e+02 +10 10235 4.269500e+02 -1.977300e+02 +12 10235 -8.272998e+01 -2.830000e+02 +10 10236 4.052800e+02 -1.980300e+02 +12 10236 -8.272998e+01 -2.830000e+02 +10 10237 -2.829600e+02 -1.976100e+02 +18 10237 -5.071900e+02 1.834099e+02 +10 10238 -1.175860e+03 -1.928300e+02 +19 10238 6.831699e+02 4.837200e+02 +10 10239 1.168930e+03 -1.916400e+02 +18 10239 6.749299e+02 1.183201e+02 +10 10240 9.415300e+02 -1.875699e+02 +18 10240 5.458601e+02 1.388201e+02 +20 10240 4.715400e+02 -7.327002e+01 +10 10241 1.109440e+03 -1.833500e+02 +12 10241 5.450601e+02 -3.468199e+02 +10 10242 -1.276300e+03 -1.597900e+02 +11 10242 -1.001050e+03 4.094200e+02 +10 10243 1.266030e+03 -1.485800e+02 +12 10243 6.967100e+02 -3.198700e+02 +10 10244 1.006340e+03 -1.445000e+02 +17 10244 1.028900e+03 1.019670e+03 +10 10245 -5.570400e+02 -1.201100e+02 +12 10245 -1.214910e+03 -1.872100e+02 +10 10246 -5.693199e+02 -1.155800e+02 +12 10246 -1.229850e+03 -1.819800e+02 +10 10247 -1.458130e+03 -2.476001e+01 +15 10247 6.114600e+02 4.242100e+02 +10 10248 1.651800e+03 -1.647998e+01 +12 10248 1.069250e+03 -2.041200e+02 +10 10249 -1.361280e+03 9.839966e+00 +19 10249 3.710601e+02 7.358600e+02 +10 10250 -1.279960e+03 2.493005e+01 +15 10250 7.530800e+02 4.827300e+02 +10 10251 -1.345360e+03 1.098800e+02 +16 10251 -5.205400e+02 6.843700e+02 +10 10252 1.750000e+02 1.002580e+03 +12 10252 -4.600601e+02 7.953000e+02 +10 10253 1.799200e+02 1.007720e+03 +12 10253 -4.554700e+02 7.996799e+02 +11 10254 2.935500e+02 -4.464301e+02 +18 10254 -6.707700e+02 -3.765100e+02 +20 10254 -5.637800e+02 -5.283600e+02 +11 10255 4.016700e+02 5.920001e+01 +12 10255 -7.933800e+02 -5.778000e+02 +11 10256 -5.090000e+02 4.068900e+02 +18 10256 -1.019210e+03 2.004600e+02 +11 10257 -5.131200e+02 2.159400e+02 +14 10257 2.197500e+02 2.435600e+02 +11 10258 -4.981200e+02 3.220800e+02 +14 10258 2.288100e+02 2.915500e+02 +20 10258 -8.707300e+02 -7.477002e+01 +11 10259 -3.184003e+01 3.516300e+02 +18 10259 -7.097800e+02 1.533500e+02 +11 10260 -1.000010e+03 3.700500e+02 +20 10260 -1.185500e+03 -4.448999e+01 +11 10261 -6.307500e+02 3.738500e+02 +20 10261 -9.451900e+02 -4.450000e+01 +11 10262 -9.172300e+02 6.173400e+02 +15 10262 8.890100e+02 4.502400e+02 +19 10262 7.148501e+02 7.009500e+02 +11 10263 -9.172300e+02 6.173400e+02 +15 10263 8.890100e+02 4.502400e+02 +19 10263 7.148501e+02 7.009500e+02 +11 10264 4.195699e+02 1.228500e+02 +20 10264 -3.460300e+02 -2.001400e+02 +11 10265 -7.156100e+02 2.664600e+02 +14 10265 1.492600e+02 2.593200e+02 +11 10266 -5.893600e+02 2.872900e+02 +14 10266 1.926700e+02 2.722600e+02 +11 10267 1.270900e+02 3.652200e+02 +12 10267 -1.035800e+03 -3.190000e+02 +11 10268 -5.330400e+02 4.942100e+02 +18 10268 -1.029780e+03 2.572800e+02 +20 10268 -8.824300e+02 2.238000e+01 +11 10269 4.133600e+02 1.403300e+02 +18 10269 -4.126000e+02 7.829956e+00 +11 10270 4.854301e+02 2.137700e+02 +18 10270 -3.533101e+02 5.703003e+01 +11 10271 -6.802200e+02 3.101400e+02 +14 10271 1.630600e+02 2.784100e+02 +11 10272 -9.567700e+02 5.504399e+02 +14 10272 -4.120001e+01 4.341899e+02 +16 10272 -4.090800e+02 5.633900e+02 +11 10273 2.615500e+02 -8.013000e+01 +18 10273 -5.222200e+02 -1.324600e+02 +11 10274 1.713600e+02 -6.481000e+01 +18 10274 -5.824800e+02 -1.218199e+02 +11 10275 5.056006e+01 -3.428998e+01 +18 10275 -6.674000e+02 -9.972998e+01 +11 10276 -7.088000e+01 -3.076001e+01 +18 10276 -7.521700e+02 -9.638000e+01 +11 10277 1.809900e+02 4.257001e+01 +18 10277 -5.741300e+02 -5.122998e+01 +11 10278 2.580100e+02 1.381300e+02 +20 10278 -4.435300e+02 -1.903800e+02 +11 10279 4.746300e+02 1.453800e+02 +12 10279 -7.083500e+02 -5.045900e+02 +11 10280 -4.737000e+02 2.022400e+02 +18 10280 -1.001390e+03 6.440991e+01 +11 10281 4.035000e+02 2.187700e+02 +18 10281 -4.196200e+02 5.910999e+01 +20 10281 -3.549200e+02 -1.469800e+02 +11 10282 -3.749500e+02 2.696600e+02 +18 10282 -9.341500e+02 1.068401e+02 +11 10283 3.403400e+02 3.089200e+02 +12 10283 -8.502500e+02 -3.722600e+02 +18 10283 -4.640100e+02 1.179600e+02 +11 10284 -6.670300e+02 3.203600e+02 +14 10284 1.677300e+02 2.835200e+02 +11 10285 9.825000e+01 3.577200e+02 +18 10285 -6.240600e+02 1.542900e+02 +11 10286 -2.294800e+02 4.037200e+02 +18 10286 -8.395800e+02 1.922100e+02 +11 10287 -5.539300e+02 4.336100e+02 +18 10287 -1.048320e+03 2.171300e+02 +11 10288 -1.914100e+02 4.538700e+02 +16 10288 1.290699e+02 5.188101e+02 +11 10289 -2.073600e+02 4.601500e+02 +14 10289 3.498600e+02 3.643400e+02 +11 10290 -9.541300e+02 -7.133002e+01 +20 10290 -1.172220e+03 -3.004399e+02 +11 10291 2.500900e+02 -5.369000e+01 +12 10291 -9.460000e+02 -6.685900e+02 +11 10292 2.500900e+02 -5.369000e+01 +12 10292 -9.460000e+02 -6.685900e+02 +11 10293 4.568199e+02 2.620001e+01 +20 10293 -3.220699e+02 -2.550699e+02 +11 10294 3.189500e+02 4.553998e+01 +18 10294 -4.820900e+02 -5.166003e+01 +11 10295 9.573600e+02 7.934998e+01 +17 10295 -1.461510e+03 2.677200e+02 +11 10296 -6.140400e+02 2.534200e+02 +14 10296 1.843400e+02 2.565800e+02 +11 10297 -5.624600e+02 2.725200e+02 +14 10297 2.031700e+02 2.669600e+02 +11 10298 -4.053400e+02 2.768900e+02 +14 10298 2.633900e+02 2.739900e+02 +11 10299 3.036200e+02 3.015900e+02 +20 10299 -4.148600e+02 -1.004301e+02 +11 10300 -6.768100e+02 3.967500e+02 +14 10300 1.661900e+02 3.154500e+02 +11 10301 -9.018500e+02 4.050601e+02 +20 10301 -1.122640e+03 -2.578998e+01 +11 10302 -7.640400e+02 4.323800e+02 +14 10302 1.369800e+02 3.265300e+02 +18 10302 -1.185910e+03 2.207100e+02 +11 10303 -3.167999e+01 4.777300e+02 +12 10303 -1.142680e+03 -2.218300e+02 +18 10303 -7.014300e+02 2.355300e+02 +11 10304 -7.191800e+02 4.781700e+02 +14 10304 1.535900e+02 3.474900e+02 +20 10304 -9.915200e+02 1.566998e+01 +11 10305 -2.325700e+02 5.301500e+02 +18 10305 -8.342000e+02 2.742500e+02 +11 10306 4.046300e+02 -4.001001e+01 +18 10306 -4.220699e+02 -1.080300e+02 +20 10306 -3.570800e+02 -2.912600e+02 +11 10307 4.046300e+02 -4.001001e+01 +20 10307 -3.570800e+02 -2.912600e+02 +11 10308 -9.803300e+02 -2.348999e+01 +15 10308 7.690601e+02 7.392999e+01 +16 10308 -4.305300e+02 2.357100e+02 +11 10309 -1.287400e+02 -2.298999e+01 +18 10309 -7.899900e+02 -9.004004e+01 +11 10310 4.727000e+02 -1.514001e+01 +12 10310 -7.128600e+02 -6.391400e+02 +11 10311 -9.963500e+02 1.750000e+01 +14 10311 -7.998999e+01 1.940500e+02 +11 10312 4.041000e+02 4.348999e+01 +18 10312 -4.201600e+02 -5.418005e+01 +11 10313 4.041000e+02 4.348999e+01 +18 10313 -4.201600e+02 -5.418005e+01 +11 10314 2.457400e+02 8.585999e+01 +18 10314 -5.304500e+02 -2.497998e+01 +11 10315 3.972300e+02 9.465997e+01 +20 10315 -3.595400e+02 -2.158400e+02 +11 10316 3.597100e+02 2.131800e+02 +12 10316 -8.328300e+02 -4.497600e+02 +20 10316 -3.820000e+02 -1.495200e+02 +11 10317 -8.901400e+02 2.309400e+02 +20 10317 -1.121610e+03 -1.255200e+02 +11 10318 3.563500e+02 2.356400e+02 +18 10318 -4.518800e+02 7.101001e+01 +11 10319 -8.710600e+02 2.650200e+02 +20 10319 -1.108180e+03 -1.053199e+02 +11 10320 4.270900e+02 2.716900e+02 +20 10320 -3.375100e+02 -1.178101e+02 +11 10321 -4.371300e+02 2.738100e+02 +16 10321 1.691003e+01 4.035601e+02 +20 10321 -8.366800e+02 -1.042800e+02 +11 10322 3.393000e+02 3.046700e+02 +12 10322 -8.516900e+02 -3.758600e+02 +18 10322 -4.647900e+02 1.152100e+02 +11 10323 -6.106800e+02 3.090500e+02 +14 10323 1.868100e+02 2.811400e+02 +11 10324 4.446899e+02 3.421200e+02 +13 10324 -1.159440e+03 9.201799e+02 +11 10325 4.446899e+02 3.421200e+02 +13 10325 -1.159440e+03 9.201799e+02 +11 10326 -9.150400e+02 3.470601e+02 +14 10326 -2.403000e+01 3.395800e+02 +15 10326 8.366801e+02 2.979500e+02 +16 10326 -3.773700e+02 4.464900e+02 +11 10327 -3.947000e+02 3.550200e+02 +14 10327 2.690200e+02 3.091500e+02 +18 10327 -9.455500e+02 1.636899e+02 +11 10328 -7.521300e+02 4.157000e+02 +14 10328 1.404300e+02 3.203700e+02 +16 10328 -1.144400e+02 4.714800e+02 +18 10328 -1.178560e+03 2.090601e+02 +11 10329 -1.472100e+02 4.410701e+02 +18 10329 -7.808400e+02 2.151000e+02 +11 10330 -7.237600e+02 4.867900e+02 +14 10330 1.519300e+02 3.510700e+02 +20 10330 -9.942400e+02 2.034003e+01 +11 10331 -2.411100e+02 5.192200e+02 +12 10331 -1.318500e+03 -1.819399e+02 +14 10331 3.393800e+02 3.875200e+02 +11 10332 -6.170500e+02 5.289200e+02 +18 10332 -1.083820e+03 2.813401e+02 +19 10332 1.255850e+03 5.758101e+02 +11 10333 6.735601e+02 -1.466700e+02 +13 10333 -1.301470e+03 -3.890002e+01 +11 10334 3.393101e+02 -3.147998e+01 +12 10334 -8.631600e+02 -6.511500e+02 +11 10335 3.393101e+02 -3.147998e+01 +12 10335 -8.631600e+02 -6.511500e+02 +11 10336 2.733900e+02 7.780029e+00 +12 10336 -9.240100e+02 -6.176300e+02 +11 10337 9.582700e+02 6.509003e+01 +17 10337 -1.460310e+03 2.427000e+02 +11 10338 3.836899e+02 6.860999e+01 +18 10338 -4.345300e+02 -3.730005e+01 +11 10339 -8.953500e+02 1.311500e+02 +20 10339 -1.129880e+03 -1.825500e+02 +11 10340 -4.337700e+02 1.901000e+02 +18 10340 -9.738900e+02 5.564001e+01 +11 10341 -3.569000e+02 1.941100e+02 +18 10341 -9.244500e+02 5.645996e+01 +11 10342 -9.212600e+02 2.341700e+02 +14 10342 2.239990e+00 2.802700e+02 +15 10342 8.816300e+02 2.228400e+02 +11 10343 -8.368500e+02 2.527400e+02 +16 10343 -1.452900e+02 3.767500e+02 +11 10344 3.692500e+02 2.577400e+02 +18 10344 -4.438800e+02 8.534009e+01 +11 10345 4.479900e+02 3.477600e+02 +13 10345 -1.148280e+03 9.403701e+02 +11 10346 -2.170500e+02 3.475701e+02 +18 10346 -8.298300e+02 1.551000e+02 +11 10347 1.993900e+02 3.624100e+02 +12 10347 -9.749100e+02 -3.240699e+02 +11 10348 2.202200e+02 3.715500e+02 +18 10348 -5.437400e+02 1.609299e+02 +11 10349 -9.169500e+02 3.848700e+02 +19 10349 7.132000e+02 4.769800e+02 +11 10350 3.776001e+01 4.022900e+02 +16 10350 2.361600e+02 4.980000e+02 +11 10351 3.003700e+02 4.356200e+02 +20 10351 -4.137200e+02 -2.594000e+01 +11 10352 -1.654900e+02 4.662800e+02 +18 10352 -7.928700e+02 2.312400e+02 +11 10353 -5.920001e+01 4.690200e+02 +18 10353 -7.189400e+02 2.305400e+02 +20 10353 -6.130200e+02 1.000977e-02 +11 10354 1.553400e+02 4.916100e+02 +12 10354 -9.877800e+02 -2.175400e+02 +11 10355 -4.896300e+02 5.225100e+02 +14 10355 2.586800e+02 3.631100e+02 +11 10356 -8.931900e+02 5.925100e+02 +14 10356 4.998779e-02 4.464800e+02 +15 10356 8.697100e+02 4.466300e+02 +11 10357 -9.772500e+02 6.213600e+02 +20 10357 -1.159950e+03 9.647998e+01 +11 10358 8.315300e+02 -2.579800e+02 +20 10358 -2.034200e+02 -4.174000e+02 +11 10359 4.322200e+02 -1.495900e+02 +20 10359 -4.761500e+02 -3.577800e+02 +11 10360 3.687900e+02 -7.964001e+01 +18 10360 -4.486100e+02 -1.335100e+02 +11 10361 4.695200e+02 -4.515002e+01 +18 10361 -3.727200e+02 -1.112700e+02 +11 10362 4.695200e+02 -4.515002e+01 +18 10362 -3.727200e+02 -1.112700e+02 +11 10363 5.254600e+02 1.032400e+02 +12 10363 -6.291600e+02 -5.441899e+02 +13 10363 -9.577900e+02 1.906899e+02 +20 10363 -2.725900e+02 -2.119200e+02 +11 10364 4.064001e+01 1.131000e+02 +18 10364 -6.744600e+02 -3.829956e+00 +11 10365 4.343700e+02 1.508500e+02 +13 10365 -1.360870e+03 4.543900e+02 +18 10365 -3.968199e+02 1.422998e+01 +20 10365 -3.358800e+02 -1.850100e+02 +11 10366 1.699301e+02 1.728300e+02 +18 10366 -5.803800e+02 3.252002e+01 +11 10367 2.530200e+02 2.054000e+02 +18 10367 -5.247400e+02 5.234998e+01 +11 10368 2.460699e+02 2.082200e+02 +18 10368 -5.287600e+02 5.491992e+01 +11 10369 2.460699e+02 2.082200e+02 +18 10369 -5.287600e+02 5.491992e+01 +11 10370 3.173900e+02 2.435600e+02 +18 10370 -4.808900e+02 7.660999e+01 +11 10371 2.146500e+02 2.561800e+02 +18 10371 -5.492800e+02 8.714001e+01 +11 10372 3.793800e+02 2.639700e+02 +20 10372 -3.683101e+02 -1.213600e+02 +11 10373 3.278700e+02 3.367200e+02 +18 10373 -4.724600e+02 1.369000e+02 +11 10374 -5.709400e+02 3.745100e+02 +18 10374 -1.060470e+03 1.794500e+02 +11 10375 -2.068100e+02 3.896799e+02 +18 10375 -8.220800e+02 1.827400e+02 +11 10376 2.612000e+01 3.992200e+02 +14 10376 4.509000e+02 3.475400e+02 +11 10377 2.902002e+01 4.106200e+02 +18 10377 -6.695500e+02 1.909600e+02 +11 10378 1.353199e+02 4.851700e+02 +12 10378 -1.002440e+03 -2.223900e+02 +18 10378 -5.911000e+02 2.362800e+02 +11 10379 -1.037000e+02 4.874900e+02 +12 10379 -1.202990e+03 -2.122100e+02 +11 10380 -5.233500e+02 4.971600e+02 +18 10380 -1.024290e+03 2.586599e+02 +11 10381 -5.816000e+02 5.479000e+02 +19 10381 1.299620e+03 5.975601e+02 +11 10382 -9.113700e+02 6.041100e+02 +20 10382 -1.119960e+03 8.659998e+01 +11 10383 -9.037100e+02 6.622900e+02 +20 10383 -1.110100e+03 1.181300e+02 +11 10384 4.586100e+02 4.298999e+01 +13 10384 -1.267980e+03 7.801001e+01 +11 10385 2.061600e+02 4.758002e+01 +18 10385 -5.572400e+02 -4.908997e+01 +20 10385 -4.739500e+02 -2.412900e+02 +11 10386 4.681899e+02 1.464300e+02 +13 10386 -1.220080e+03 4.100400e+02 +11 10387 4.392700e+02 1.512100e+02 +18 10387 -3.930699e+02 1.455005e+01 +11 10388 4.646400e+02 2.117700e+02 +13 10388 -1.228100e+03 6.250801e+02 +11 10389 4.389301e+02 3.097400e+02 +13 10389 -1.326260e+03 9.663501e+02 +11 10390 4.403199e+02 3.345100e+02 +13 10390 -1.175380e+03 8.977400e+02 +11 10391 -2.631400e+02 3.431600e+02 +18 10391 -8.604200e+02 1.530701e+02 +11 10392 -1.689700e+02 4.941700e+02 +18 10392 -7.938200e+02 2.499700e+02 +11 10393 7.351000e+02 -2.231700e+02 +12 10393 -8.310200e+02 -8.153900e+02 +13 10393 -1.062990e+03 -3.562900e+02 +11 10394 3.502700e+02 -1.009800e+02 +12 10394 -8.538700e+02 -7.087700e+02 +11 10395 3.753600e+02 -9.304999e+01 +13 10395 -1.614260e+03 -3.238600e+02 +11 10396 3.490000e+02 1.781000e+01 +13 10396 -1.708090e+03 5.763000e+01 +11 10397 3.774600e+02 7.583002e+01 +13 10397 -1.595910e+03 2.432100e+02 +11 10398 4.143101e+02 1.985200e+02 +13 10398 -1.437360e+03 6.261500e+02 +11 10399 3.852200e+02 2.015500e+02 +13 10399 -1.554030e+03 6.547300e+02 +11 10400 4.171600e+02 2.346100e+02 +13 10400 -1.425320e+03 7.465200e+02 +11 10401 4.130300e+02 3.213800e+02 +13 10401 -1.380940e+03 9.779700e+02 +11 10402 -9.113600e+02 3.447900e+02 +19 10402 6.325100e+02 4.563500e+02 +11 10403 4.272000e+02 3.704000e+02 +13 10403 -1.212250e+03 1.012920e+03 +11 10404 4.358900e+02 3.751700e+02 +13 10404 -1.183400e+03 1.025080e+03 +11 10405 -9.162700e+02 3.970601e+02 +19 10405 6.288701e+02 5.080801e+02 +11 10406 -6.593800e+02 4.475800e+02 +19 10406 1.204150e+03 4.932200e+02 +11 10407 -3.133600e+02 4.744800e+02 +12 10407 -1.362290e+03 -2.160900e+02 +11 10408 -4.889300e+02 5.344100e+02 +19 10408 1.406480e+03 5.891100e+02 +12 10409 4.912600e+02 -5.476100e+02 +17 10409 1.163150e+03 3.935500e+02 +12 10410 1.104960e+03 -3.533000e+02 +20 10410 9.830300e+02 -8.616003e+01 +12 10411 5.752100e+02 -6.399700e+02 +18 10411 7.011899e+02 -1.054000e+02 +20 10411 6.088101e+02 -2.809600e+02 +12 10412 5.752100e+02 -6.399700e+02 +18 10412 7.011899e+02 -1.054000e+02 +20 10412 6.088101e+02 -2.809600e+02 +12 10413 6.118701e+02 -5.694600e+02 +17 10413 1.478790e+03 3.724000e+02 +18 10413 7.327700e+02 -4.493005e+01 +12 10414 7.553000e+02 -3.160800e+02 +20 10414 7.912400e+02 -5.893994e+01 +12 10415 8.343101e+02 -4.027300e+02 +18 10415 9.238999e+02 8.103003e+01 +20 10415 7.928201e+02 -1.198199e+02 +12 10416 6.133601e+02 -6.733900e+02 +18 10416 7.286201e+02 -1.317500e+02 +20 10416 6.348301e+02 -3.029600e+02 +12 10417 6.133601e+02 -6.733900e+02 +18 10417 7.286201e+02 -1.317500e+02 +20 10417 6.348301e+02 -3.029600e+02 +12 10418 5.474500e+02 -6.726400e+02 +18 10418 6.768301e+02 -1.301300e+02 +20 10418 5.876799e+02 -3.022300e+02 +12 10419 5.474500e+02 -6.726400e+02 +18 10419 6.768301e+02 -1.301300e+02 +20 10419 5.876799e+02 -3.022300e+02 +12 10420 5.474500e+02 -6.726400e+02 +18 10420 6.768301e+02 -1.301300e+02 +20 10420 5.876799e+02 -3.022300e+02 +12 10421 -2.116600e+02 -6.080500e+02 +20 10421 7.916003e+01 -2.578199e+02 +12 10422 5.413400e+02 -4.296899e+02 +17 10422 1.299920e+03 6.940200e+02 +18 10422 6.734099e+02 6.044995e+01 +20 10422 5.810801e+02 -1.378700e+02 +12 10423 7.610200e+02 -4.274000e+02 +18 10423 9.241799e+02 6.164001e+01 +12 10424 1.026240e+03 -4.196000e+02 +20 10424 9.276899e+02 -1.322200e+02 +12 10425 1.574301e+02 -6.735800e+02 +18 10425 3.235500e+02 -1.264500e+02 +12 10426 5.722200e+02 -6.496500e+02 +18 10426 6.988201e+02 -1.127500e+02 +12 10427 -7.735999e+01 -6.055601e+02 +17 10427 -5.843700e+02 2.119500e+02 +18 10427 1.479399e+02 -7.015002e+01 +12 10428 -1.427800e+02 -4.961300e+02 +17 10428 -7.452600e+02 4.865801e+02 +12 10429 9.916599e+02 -4.475400e+02 +20 10429 9.027600e+02 -1.481000e+02 +12 10430 8.535500e+02 -2.753101e+02 +20 10430 8.052300e+02 -3.225000e+01 +12 10431 -1.460910e+03 -2.141000e+02 +14 10431 2.698900e+02 3.491600e+02 +12 10432 9.610801e+02 -1.983300e+02 +18 10432 1.038070e+03 2.481799e+02 +12 10433 -4.709600e+02 5.627800e+02 +18 10433 -6.818994e+01 8.850500e+02 +20 10433 -5.435999e+01 5.519100e+02 +12 10434 4.328900e+02 -7.110800e+02 +20 10434 5.076200e+02 -3.276899e+02 +12 10435 5.755701e+02 -6.204600e+02 +17 10435 1.383730e+03 2.262800e+02 +18 10435 7.016499e+02 -8.916003e+01 +20 10435 6.093899e+02 -2.670000e+02 +12 10436 5.583201e+02 -5.540800e+02 +17 10436 1.338680e+03 3.896699e+02 +12 10437 -1.440400e+02 -4.522600e+02 +17 10437 -7.580000e+02 5.950801e+02 +12 10438 -8.834600e+02 -3.977200e+02 +18 10438 -4.875500e+02 9.454004e+01 +20 10438 -4.129200e+02 -1.160300e+02 +12 10439 5.544099e+02 -6.630000e+02 +17 10439 1.321990e+03 1.233199e+02 +18 10439 6.842500e+02 -1.221200e+02 +20 10439 5.940400e+02 -2.958300e+02 +12 10440 4.190100e+02 -3.961100e+02 +17 10440 8.321299e+02 7.620200e+02 +18 10440 5.760000e+02 9.232007e+01 +20 10440 4.981100e+02 -1.127400e+02 +12 10441 4.369301e+02 -3.041200e+02 +18 10441 5.887000e+02 1.645601e+02 +12 10442 7.319500e+02 -2.368700e+02 +18 10442 8.419900e+02 2.178800e+02 +12 10443 -1.153650e+03 -2.250601e+02 +18 10443 -7.106200e+02 2.344399e+02 +12 10444 -1.275700e+03 -1.785300e+02 +14 10444 3.623600e+02 3.918300e+02 +12 10445 -4.529100e+02 7.543101e+02 +18 10445 -5.709998e+01 1.049540e+03 +20 10445 -4.284998e+01 6.863800e+02 +12 10446 -6.005100e+02 -9.356700e+02 +20 10446 -5.248999e+01 -4.805699e+02 +12 10447 4.853900e+02 -6.848400e+02 +18 10447 6.299700e+02 -1.389700e+02 +12 10448 -1.439399e+02 -6.685400e+02 +18 10448 9.368005e+01 -1.186400e+02 +12 10449 4.578900e+02 -6.638400e+02 +20 10449 5.254100e+02 -2.964399e+02 +12 10450 -3.761200e+02 -6.415300e+02 +20 10450 3.187000e+01 -2.797500e+02 +12 10451 7.454800e+02 -5.426700e+02 +18 10451 9.722800e+02 -3.056006e+01 +20 10451 8.357100e+02 -2.140900e+02 +12 10452 -1.858300e+02 -4.687000e+02 +17 10452 -8.628800e+02 5.566000e+02 +12 10453 1.245610e+03 -1.440601e+02 +20 10453 1.085290e+03 5.747998e+01 +12 10454 1.243710e+03 -1.329600e+02 +20 10454 1.084380e+03 6.723999e+01 +12 10455 3.987300e+02 -6.975500e+02 +17 10455 8.957100e+02 3.698999e+01 +12 10456 3.987300e+02 -6.975500e+02 +17 10456 8.957100e+02 3.698999e+01 +12 10457 5.789500e+02 -6.842100e+02 +18 10457 7.028000e+02 -1.401000e+02 +20 10457 6.108301e+02 -3.104900e+02 +12 10458 -1.927500e+02 -5.974900e+02 +17 10458 -8.768800e+02 2.387100e+02 +12 10459 1.160999e+01 -5.882800e+02 +18 10459 2.128700e+02 -5.701001e+01 +12 10460 -9.708500e+02 -5.788300e+02 +18 10460 -5.504200e+02 -4.530005e+01 +20 10460 -4.680900e+02 -2.378500e+02 +12 10461 4.971100e+02 -5.546500e+02 +17 10461 1.179670e+03 3.884399e+02 +12 10462 9.492500e+02 -5.386000e+02 +18 10462 1.015470e+03 -2.942004e+01 +20 10462 8.722400e+02 -2.127400e+02 +12 10463 7.925000e+01 -5.191801e+02 +18 10463 2.219700e+02 -2.469971e+00 +12 10464 9.485100e+02 -5.076200e+02 +18 10464 1.016070e+03 -4.400024e+00 +12 10465 9.485100e+02 -5.076200e+02 +18 10465 1.016070e+03 -4.400024e+00 +12 10466 1.035990e+03 -4.964100e+02 +20 10466 9.335701e+02 -1.843900e+02 +12 10467 -2.039200e+02 -4.813000e+02 +18 10467 9.379004e+01 2.982996e+01 +12 10468 -4.505005e+01 -4.595699e+02 +18 10468 1.721300e+02 4.593994e+01 +20 10468 1.527300e+02 -1.549800e+02 +12 10469 5.105601e+02 -4.588800e+02 +17 10469 1.224780e+03 6.244700e+02 +20 10469 5.643999e+02 -1.562100e+02 +12 10470 1.100930e+03 -4.537600e+02 +20 10470 9.797000e+02 -1.555000e+02 +12 10471 -1.900601e+02 -4.515100e+02 +17 10471 -7.277700e+02 5.993101e+02 +12 10472 -7.833300e+02 -4.137400e+02 +18 10472 -4.178199e+02 8.494995e+01 +20 10472 -3.533400e+02 -1.245400e+02 +12 10473 9.998301e+02 -4.135900e+02 +20 10473 1.049750e+03 -1.241200e+02 +12 10474 -7.645000e+02 -3.728900e+02 +18 10474 -4.142000e+02 1.169199e+02 +12 10475 9.313000e+02 -3.684700e+02 +18 10475 1.007330e+03 1.077100e+02 +20 10475 8.611899e+02 -9.601001e+01 +12 10476 9.395500e+02 -3.617900e+02 +18 10476 1.014000e+03 1.133401e+02 +20 10476 8.669600e+02 -9.151001e+01 +12 10477 8.703501e+02 -3.612400e+02 +18 10477 9.558301e+02 1.150601e+02 +20 10477 8.180500e+02 -9.067004e+01 +12 10478 8.703501e+02 -3.612400e+02 +20 10478 8.180500e+02 -9.067004e+01 +12 10479 1.137100e+03 -3.239800e+02 +20 10479 1.007020e+03 -6.684998e+01 +12 10480 1.023120e+03 -2.922600e+02 +20 10480 9.263999e+02 -4.417004e+01 +12 10481 9.870100e+02 -2.518700e+02 +20 10481 9.008000e+02 -1.492999e+01 +12 10482 1.064640e+03 -2.486801e+02 +20 10482 9.556899e+02 -1.310999e+01 +12 10483 1.009380e+03 -2.430300e+02 +20 10483 9.172600e+02 -9.900024e+00 +12 10484 -1.296960e+03 -1.884100e+02 +18 10484 -8.239100e+02 2.624600e+02 +12 10485 -3.894100e+02 5.492300e+02 +18 10485 -5.600586e-01 8.744600e+02 +20 10485 6.050049e+00 5.411200e+02 +12 10486 -4.522600e+02 8.454200e+02 +20 10486 -4.505005e+01 7.509299e+02 +12 10487 4.300100e+02 -7.063300e+02 +18 10487 5.796299e+02 -1.549600e+02 +20 10487 5.052800e+02 -3.249200e+02 +12 10488 4.714600e+02 -6.952500e+02 +18 10488 6.141499e+02 -1.476700e+02 +20 10488 5.352800e+02 -3.177500e+02 +12 10489 5.680100e+02 -6.922500e+02 +18 10489 6.928201e+02 -1.463300e+02 +20 10489 5.998501e+02 -3.161600e+02 +12 10490 5.211300e+02 -6.920500e+02 +17 10490 1.237860e+03 5.315002e+01 +20 10490 5.703000e+02 -3.155500e+02 +12 10491 5.211300e+02 -6.920500e+02 +17 10491 1.237860e+03 5.315002e+01 +20 10491 5.703000e+02 -3.155500e+02 +12 10492 6.378999e+02 -6.863101e+02 +20 10492 6.523000e+02 -3.118500e+02 +12 10493 5.178800e+02 -6.857800e+02 +17 10493 1.228570e+03 6.892004e+01 +18 10493 6.539700e+02 -1.405699e+02 +20 10493 5.680000e+02 -3.109200e+02 +12 10494 5.709700e+02 -6.848199e+02 +18 10494 6.962100e+02 -1.404200e+02 +20 10494 6.051101e+02 -3.108101e+02 +12 10495 5.709700e+02 -6.848199e+02 +20 10495 6.051101e+02 -3.108101e+02 +12 10496 4.810699e+02 -6.847900e+02 +18 10496 6.228401e+02 -1.390699e+02 +20 10496 5.432100e+02 -3.102700e+02 +12 10497 1.682400e+02 -6.837700e+02 +20 10497 2.896100e+02 -3.080300e+02 +12 10498 5.864500e+02 -6.600000e+02 +18 10498 7.102700e+02 -1.208101e+02 +12 10499 6.720400e+02 -6.337600e+02 +18 10499 7.814600e+02 -1.014200e+02 +20 10499 6.763000e+02 -2.764399e+02 +12 10500 6.720400e+02 -6.337600e+02 +18 10500 7.814600e+02 -1.014200e+02 +12 10501 5.620701e+02 -6.336700e+02 +17 10501 1.345170e+03 1.969299e+02 +18 10501 6.910601e+02 -9.929004e+01 +20 10501 5.994800e+02 -2.756400e+02 +12 10502 5.370200e+02 -6.177200e+02 +17 10502 1.273480e+03 2.319500e+02 +12 10503 -7.644400e+02 -6.113600e+02 +20 10503 -3.409100e+02 -2.590200e+02 +12 10504 1.033350e+03 -5.962000e+02 +20 10504 1.000850e+03 -2.521100e+02 +12 10505 4.551500e+02 -5.665900e+02 +20 10505 5.246700e+02 -2.297800e+02 +12 10506 -9.783997e+01 -5.621899e+02 +13 10506 1.372490e+03 2.225801e+02 +17 10506 -6.387400e+02 3.221599e+02 +12 10507 5.789900e+02 -5.525699e+02 +17 10507 1.398360e+03 3.973700e+02 +18 10507 7.066699e+02 -3.542004e+01 +20 10507 6.116201e+02 -2.205300e+02 +12 10508 9.539700e+02 -5.470699e+02 +18 10508 1.019190e+03 -3.647998e+01 +20 10508 8.758201e+02 -2.188101e+02 +12 10509 9.383997e+01 -5.454700e+02 +18 10509 2.818400e+02 -2.342004e+01 +12 10510 -5.296997e+01 -5.418800e+02 +20 10510 1.475900e+02 -2.115500e+02 +12 10511 4.497000e+02 -5.410601e+02 +18 10511 5.996299e+02 -2.463000e+01 +20 10511 5.195200e+02 -2.122100e+02 +12 10512 5.001400e+02 -5.371801e+02 +17 10512 1.186840e+03 4.319199e+02 +18 10512 6.415200e+02 -2.079004e+01 +12 10513 9.479099e+02 -5.222800e+02 +18 10513 1.014670e+03 -1.266003e+01 +20 10513 8.714900e+02 -2.021200e+02 +12 10514 9.479099e+02 -5.222800e+02 +18 10514 1.016070e+03 -4.400024e+00 +20 10514 8.715000e+02 -2.019700e+02 +12 10515 1.187060e+03 -4.996400e+02 +20 10515 9.696299e+02 -1.878199e+02 +12 10516 1.187060e+03 -4.996400e+02 +20 10516 9.696299e+02 -1.878199e+02 +12 10517 4.890100e+02 -4.962400e+02 +18 10517 6.330701e+02 1.101001e+01 +12 10518 5.070699e+02 -4.946700e+02 +17 10518 1.209410e+03 5.363900e+02 +18 10518 6.478000e+02 1.240002e+01 +12 10519 4.267900e+02 -4.810000e+02 +17 10519 9.859199e+02 5.680901e+02 +12 10520 -8.611000e+02 -4.792500e+02 +18 10520 -4.700000e+02 3.325000e+01 +12 10521 9.165002e+01 -4.725400e+02 +18 10521 2.795699e+02 3.442004e+01 +12 10522 -2.862000e+01 -4.730699e+02 +18 10522 1.842000e+02 3.487000e+01 +12 10523 -2.862000e+01 -4.730699e+02 +17 10523 -5.019200e+02 5.354199e+02 +18 10523 1.842000e+02 3.487000e+01 +12 10524 1.143590e+03 -4.725400e+02 +20 10524 1.008930e+03 -1.682900e+02 +12 10525 -8.704800e+02 -4.562500e+02 +18 10525 -4.765500e+02 5.228003e+01 +12 10526 -8.704800e+02 -4.562500e+02 +18 10526 -4.765500e+02 5.228003e+01 +12 10527 1.115580e+03 -4.549900e+02 +20 10527 9.895500e+02 -1.568300e+02 +12 10528 9.448701e+02 -4.526500e+02 +18 10528 1.015260e+03 3.869995e+01 +20 10528 8.698000e+02 -1.556000e+02 +12 10529 5.315100e+02 -4.223101e+02 +17 10529 1.274670e+03 7.167600e+02 +20 10529 5.783000e+02 -1.330500e+02 +12 10530 1.002770e+03 -4.015699e+02 +20 10530 9.110000e+02 -1.193400e+02 +12 10531 9.803301e+02 -4.022300e+02 +18 10531 1.047400e+03 7.967993e+01 +20 10531 8.963401e+02 -1.196000e+02 +12 10532 1.098650e+03 -3.740000e+02 +20 10532 9.798701e+02 -1.004900e+02 +12 10533 8.392000e+02 -3.729399e+02 +20 10533 7.967000e+02 -9.815002e+01 +12 10534 8.912500e+02 -3.711300e+02 +20 10534 8.325601e+02 -9.728003e+01 +12 10535 4.221700e+02 -3.644800e+02 +17 10535 9.753401e+02 8.532400e+02 +18 10535 5.791499e+02 1.168600e+02 +12 10536 5.390400e+02 -3.449200e+02 +20 10536 5.828701e+02 -7.763000e+01 +12 10537 7.130005e+00 -3.260200e+02 +13 10537 1.645790e+03 1.089760e+03 +12 10538 -5.945996e+01 -2.981899e+02 +18 10538 1.420601e+02 1.747700e+02 +20 10538 1.259100e+02 -4.470996e+01 +12 10539 7.683799e+02 -2.967200e+02 +18 10539 8.716499e+02 1.685500e+02 +12 10540 8.269099e+02 -2.932700e+02 +18 10540 9.203101e+02 1.702000e+02 +12 10541 9.706101e+02 -2.903400e+02 +18 10541 1.042260e+03 1.714800e+02 +20 10541 8.892800e+02 -4.218994e+01 +12 10542 7.241101e+02 -2.470699e+02 +18 10542 8.350300e+02 2.096200e+02 +20 10542 7.145500e+02 -1.137000e+01 +12 10543 9.568601e+02 -2.453101e+02 +18 10543 1.032240e+03 2.085300e+02 +12 10544 1.205060e+03 -2.148500e+02 +20 10544 1.056680e+03 8.760010e+00 +12 10545 1.150220e+03 -1.911700e+02 +20 10545 1.017830e+03 2.534998e+01 +12 10546 1.172790e+03 -1.897600e+02 +20 10546 1.024250e+03 2.523999e+01 +12 10547 2.607800e+02 -9.839500e+02 +18 10547 6.447600e+02 -3.716200e+02 +12 10548 2.455100e+02 -9.772300e+02 +18 10548 6.316299e+02 -3.659500e+02 +20 10548 5.624500e+02 -5.075699e+02 +12 10549 -4.410800e+02 -6.782500e+02 +13 10549 7.113401e+02 2.082300e+02 +20 10549 -1.219995e+01 -3.052300e+02 +12 10550 4.207400e+02 -6.749900e+02 +18 10550 5.718899e+02 -1.303300e+02 +12 10551 4.657000e+02 -6.642800e+02 +17 10551 9.101399e+02 1.222100e+02 +12 10552 5.699299e+02 -6.605699e+02 +17 10552 1.363510e+03 1.307100e+02 +18 10552 6.962100e+02 -1.212800e+02 +12 10553 5.208101e+02 -6.608800e+02 +17 10553 1.237090e+03 1.294600e+02 +18 10553 6.558999e+02 -1.208500e+02 +12 10554 5.748201e+02 -6.561400e+02 +17 10554 1.376080e+03 1.415200e+02 +18 10554 7.005300e+02 -1.177500e+02 +20 10554 6.082200e+02 -2.912400e+02 +12 10555 5.761201e+02 -6.456899e+02 +17 10555 1.380070e+03 1.667900e+02 +20 10555 6.089399e+02 -2.842500e+02 +12 10556 5.761201e+02 -6.456899e+02 +17 10556 1.380070e+03 1.667900e+02 +20 10556 6.089399e+02 -2.842500e+02 +12 10557 6.762200e+02 -6.409399e+02 +18 10557 7.846799e+02 -1.073600e+02 +12 10558 -4.030029e+00 -6.405200e+02 +18 10558 2.045500e+02 -9.830005e+01 +20 10558 1.821500e+02 -2.784500e+02 +12 10559 6.620801e+02 -6.395601e+02 +18 10559 7.733301e+02 -1.056000e+02 +12 10560 6.615300e+02 -6.283800e+02 +18 10560 7.733000e+02 -9.632996e+01 +12 10561 4.641000e+02 -6.129700e+02 +17 10561 1.082330e+03 2.420701e+02 +18 10561 6.095701e+02 -8.244995e+01 +12 10562 4.525699e+02 -6.127600e+02 +17 10562 1.044050e+03 2.431300e+02 +18 10562 5.994500e+02 -8.232996e+01 +20 10562 5.212800e+02 -2.613500e+02 +12 10563 5.739199e+02 -5.993000e+02 +17 10563 1.377060e+03 2.785801e+02 +18 10563 7.010500e+02 -7.210999e+01 +20 10563 6.072900e+02 -2.527300e+02 +12 10564 1.671300e+02 -5.946000e+02 +18 10564 3.296200e+02 -6.370996e+01 +12 10565 -1.937100e+02 -5.689301e+02 +18 10565 5.382996e+01 -4.059998e+01 +12 10566 -5.271997e+01 -5.635200e+02 +13 10566 1.539980e+03 2.080500e+02 +18 10566 1.640699e+02 -3.681995e+01 +12 10567 8.275000e+01 -5.621500e+02 +18 10567 2.718700e+02 -3.709998e+01 +12 10568 -8.737300e+02 -5.609200e+02 +18 10568 -4.780400e+02 -3.168994e+01 +12 10569 -1.668005e+01 -5.579100e+02 +18 10569 1.930000e+02 -3.290002e+01 +12 10570 4.979200e+02 -5.560200e+02 +17 10570 1.181680e+03 3.844600e+02 +18 10570 6.388301e+02 -3.695996e+01 +12 10571 1.003110e+03 -5.496600e+02 +20 10571 9.796699e+02 -2.196801e+02 +12 10572 6.528799e+02 -5.499600e+02 +18 10572 7.683601e+02 -3.433997e+01 +20 10572 6.640100e+02 -2.197200e+02 +12 10573 9.000801e+02 -5.481000e+02 +18 10573 9.733999e+02 -3.609998e+01 +20 10573 8.370200e+02 -2.195000e+02 +12 10574 6.630801e+02 -5.413800e+02 +18 10574 7.764099e+02 -2.794995e+01 +12 10575 6.259700e+02 -5.398500e+02 +18 10575 7.466799e+02 -2.598999e+01 +20 10575 6.445901e+02 -2.120400e+02 +12 10576 6.680701e+02 -5.386300e+02 +18 10576 7.808999e+02 -2.494995e+01 +12 10577 6.276399e+02 -5.241899e+02 +20 10577 6.464299e+02 -2.010200e+02 +12 10578 4.384000e+02 -5.188800e+02 +17 10578 1.010220e+03 4.711200e+02 +18 10578 5.899900e+02 -6.689941e+00 +20 10578 5.113199e+02 -1.968400e+02 +12 10579 6.614199e+02 -5.017400e+02 +18 10579 7.761899e+02 4.900024e+00 +12 10580 -1.824800e+02 -4.978400e+02 +18 10580 6.209998e+01 1.613000e+01 +12 10581 1.565699e+02 -4.949600e+02 +18 10581 3.240000e+02 1.597998e+01 +12 10582 1.022960e+03 -4.945200e+02 +20 10582 9.239800e+02 -1.839100e+02 +12 10583 1.022960e+03 -4.945200e+02 +20 10583 9.239800e+02 -1.839100e+02 +12 10584 -6.737600e+02 -4.940100e+02 +13 10584 -1.098880e+03 4.208600e+02 +18 10584 -3.492900e+02 2.133997e+01 +12 10585 1.098850e+03 -4.927100e+02 +20 10585 9.781799e+02 -1.824500e+02 +12 10586 8.969099e+02 -4.913700e+02 +20 10586 8.360000e+02 -1.802300e+02 +12 10587 8.969099e+02 -4.913700e+02 +20 10587 7.822900e+02 -1.813400e+02 +12 10588 3.614001e+01 -4.896000e+02 +20 10588 2.081300e+02 -1.757300e+02 +12 10589 6.659500e+02 -4.681899e+02 +18 10589 7.812700e+02 3.176001e+01 +12 10590 1.034910e+03 -4.578300e+02 +20 10590 1.073850e+03 -1.549000e+02 +12 10591 -1.220000e+02 -4.577600e+02 +20 10591 1.020100e+02 -1.540699e+02 +12 10592 4.411801e+02 -4.523700e+02 +18 10592 5.941201e+02 4.673999e+01 +12 10593 4.411801e+02 -4.523700e+02 +18 10593 5.941201e+02 4.673999e+01 +12 10594 -9.818005e+01 -4.482900e+02 +18 10594 1.312600e+02 5.450000e+01 +12 10595 4.558300e+02 -4.469301e+02 +20 10595 5.248199e+02 -1.479100e+02 +12 10596 5.786499e+02 -4.141700e+02 +18 10596 7.092400e+02 7.584998e+01 +12 10597 4.186899e+02 -3.913000e+02 +20 10597 4.975500e+02 -1.097200e+02 +12 10598 4.232900e+02 -3.864100e+02 +17 10598 9.912600e+02 8.068900e+02 +20 10598 5.016300e+02 -1.061300e+02 +12 10599 5.043400e+02 -3.830601e+02 +20 10599 5.628201e+02 -1.044800e+02 +12 10600 6.906599e+02 -3.784700e+02 +18 10600 8.436499e+02 1.035200e+02 +12 10601 5.180400e+02 -3.778600e+02 +17 10601 1.274170e+03 8.273800e+02 +18 10601 6.599700e+02 1.054800e+02 +12 10602 4.075200e+02 -3.764600e+02 +20 10602 4.898199e+02 -9.927002e+01 +12 10603 5.768601e+02 -3.708600e+02 +18 10603 7.093501e+02 1.107900e+02 +12 10604 5.758501e+02 -3.568500e+02 +18 10604 7.088301e+02 1.217400e+02 +20 10604 6.096499e+02 -8.678003e+01 +12 10605 -1.381200e+02 -3.245400e+02 +17 10605 -9.945200e+02 8.625100e+02 +12 10606 6.787100e+02 -2.732600e+02 +18 10606 7.960400e+02 1.884199e+02 +12 10607 9.533999e+02 -2.683300e+02 +18 10607 1.029200e+03 1.906400e+02 +12 10608 6.794700e+02 -2.575800e+02 +18 10608 7.970300e+02 2.022800e+02 +12 10609 6.972500e+02 -2.518199e+02 +18 10609 8.119600e+02 2.059399e+02 +12 10610 1.183250e+03 -2.021100e+02 +20 10610 1.041960e+03 1.710999e+01 +12 10611 1.156950e+03 -1.478400e+02 +20 10611 1.011920e+03 5.546997e+01 +12 10612 9.490400e+02 -1.468101e+02 +20 10612 1.070190e+03 6.625000e+01 +12 10613 -5.271600e+02 -7.300699e+02 +13 10613 3.252300e+02 -2.294995e+01 +12 10614 -5.271600e+02 -7.300699e+02 +13 10614 3.225100e+02 -2.293994e+01 +12 10615 4.763000e+02 -7.022800e+02 +20 10615 5.385601e+02 -3.221300e+02 +12 10616 4.782600e+02 -6.796200e+02 +17 10616 1.123100e+03 8.240002e+01 +18 10616 6.200500e+02 -1.349500e+02 +20 10616 5.400100e+02 -3.067500e+02 +12 10617 -7.391700e+02 -6.735000e+02 +20 10617 -3.264100e+02 -3.011100e+02 +12 10618 4.545000e+02 -6.616700e+02 +20 10618 5.211801e+02 -2.950100e+02 +12 10619 6.052000e+02 -6.527200e+02 +18 10619 6.659099e+02 -1.145000e+02 +20 10619 5.794299e+02 -2.887200e+02 +12 10620 5.956201e+02 -6.526100e+02 +20 10620 6.257900e+02 -2.888300e+02 +12 10621 5.721599e+02 -6.514100e+02 +17 10621 1.368530e+03 1.535801e+02 +18 10621 6.983799e+02 -1.138300e+02 +12 10622 1.049500e+03 -6.507400e+02 +20 10622 1.011360e+03 -2.894800e+02 +12 10623 5.791299e+02 -6.509700e+02 +18 10623 7.047800e+02 -1.135100e+02 +12 10624 -1.041700e+02 -6.503500e+02 +20 10624 1.152800e+02 -2.851300e+02 +12 10625 6.432200e+02 -6.485100e+02 +17 10625 1.555820e+03 1.618700e+02 +18 10625 7.574800e+02 -1.126500e+02 +20 10625 6.560200e+02 -2.863900e+02 +12 10626 1.053120e+03 -6.460000e+02 +20 10626 1.014080e+03 -2.864100e+02 +12 10627 5.823401e+02 -6.455800e+02 +17 10627 1.395590e+03 1.675200e+02 +12 10628 5.823401e+02 -6.455800e+02 +17 10628 1.395590e+03 1.675200e+02 +12 10629 1.800800e+02 -6.449800e+02 +20 10629 2.979700e+02 -2.817500e+02 +12 10630 5.724600e+02 -6.415699e+02 +17 10630 1.369760e+03 1.777400e+02 +12 10631 6.083201e+02 -6.311899e+02 +18 10631 7.387900e+02 -9.856995e+01 +12 10632 4.060400e+02 -6.320601e+02 +17 10632 9.179199e+02 1.973600e+02 +20 10632 4.889399e+02 -2.733000e+02 +12 10633 6.662500e+02 -6.304000e+02 +18 10633 7.768501e+02 -9.821997e+01 +12 10634 6.662500e+02 -6.304000e+02 +18 10634 7.768501e+02 -9.821997e+01 +12 10635 2.834998e+01 -6.249399e+02 +18 10635 2.281500e+02 -8.693994e+01 +20 10635 2.026000e+02 -2.686400e+02 +12 10636 3.956200e+02 -6.238600e+02 +18 10636 5.505901e+02 -8.938000e+01 +12 10637 4.454700e+02 -6.128700e+02 +20 10637 5.160699e+02 -2.610200e+02 +12 10638 -8.496100e+02 -6.111000e+02 +20 10638 -3.905699e+02 -2.593199e+02 +12 10639 1.556000e+02 -5.906200e+02 +18 10639 3.204000e+02 -6.012000e+01 +12 10640 -7.319500e+02 -5.890800e+02 +18 10640 -3.833300e+02 -5.373999e+01 +12 10641 5.832500e+02 -5.877300e+02 +17 10641 1.403080e+03 3.081100e+02 +18 10641 7.088501e+02 -6.338000e+01 +20 10641 6.140200e+02 -2.444100e+02 +12 10642 4.440300e+02 -5.844200e+02 +17 10642 1.021990e+03 3.123401e+02 +18 10642 5.925601e+02 -5.907996e+01 +12 10643 9.015002e+01 -5.624800e+02 +18 10643 2.780601e+02 -3.756995e+01 +12 10644 5.674800e+02 -5.462200e+02 +18 10644 6.974299e+02 -2.953003e+01 +12 10645 6.583999e+02 -5.452800e+02 +18 10645 7.726201e+02 -3.075000e+01 +12 10646 5.219971e+00 -5.454200e+02 +18 10646 2.106300e+02 -2.306006e+01 +12 10647 6.323301e+02 -5.402100e+02 +18 10647 7.508000e+02 -2.631006e+01 +12 10648 9.478799e+02 -5.321700e+02 +18 10648 1.014760e+03 -2.502002e+01 +12 10649 -6.416700e+02 -5.301801e+02 +16 10649 6.879399e+02 3.096200e+02 +12 10650 4.250200e+02 -5.296801e+02 +17 10650 9.776599e+02 4.446200e+02 +12 10651 4.905699e+02 -5.278700e+02 +17 10651 1.162410e+03 4.528101e+02 +12 10652 4.045601e+02 -5.269100e+02 +17 10652 9.151799e+02 4.513201e+02 +18 10652 5.605000e+02 -1.285999e+01 +20 10652 4.872200e+02 -2.020800e+02 +12 10653 -1.477600e+02 -5.256300e+02 +18 10653 9.119995e+01 -6.380005e+00 +12 10654 1.707400e+02 -5.172200e+02 +18 10654 3.332300e+02 -3.199463e-01 +12 10655 1.080770e+03 -5.013600e+02 +20 10655 1.035540e+03 -1.885900e+02 +12 10656 4.779399e+02 -4.941000e+02 +18 10656 6.244700e+02 1.225000e+01 +20 10656 5.407000e+02 -1.808199e+02 +12 10657 -2.064700e+02 -4.934301e+02 +16 10657 9.806500e+02 3.720300e+02 +17 10657 -9.104600e+02 4.974800e+02 +12 10658 1.179890e+03 -4.919500e+02 +20 10658 1.035130e+03 -1.827400e+02 +12 10659 -1.868300e+02 -4.833000e+02 +18 10659 6.155005e+01 2.729004e+01 +12 10660 6.553401e+02 -4.622500e+02 +18 10660 7.727300e+02 3.651001e+01 +12 10661 1.178570e+03 -4.518800e+02 +20 10661 1.034250e+03 -1.539600e+02 +12 10662 5.949199e+02 -4.447800e+02 +17 10662 1.442400e+03 6.601899e+02 +18 10662 7.230300e+02 5.093005e+01 +20 10662 6.230500e+02 -1.467300e+02 +12 10663 -1.544100e+02 -4.283900e+02 +17 10663 -7.794300e+02 6.573400e+02 +12 10664 9.814500e+02 -4.110500e+02 +20 10664 9.659700e+02 -1.245100e+02 +12 10665 4.687000e+02 -4.100601e+02 +18 10665 6.177100e+02 8.062000e+01 +12 10666 1.079880e+03 -4.086899e+02 +20 10666 9.659700e+02 -1.245100e+02 +12 10667 5.026899e+02 -4.080100e+02 +17 10667 1.203550e+03 7.501400e+02 +18 10667 6.464199e+02 8.159998e+01 +12 10668 4.673700e+02 -3.892200e+02 +17 10668 1.108170e+03 7.962700e+02 +12 10669 9.853701e+02 -3.828900e+02 +20 10669 8.993501e+02 -1.062400e+02 +12 10670 5.211500e+02 -3.829700e+02 +18 10670 6.666799e+02 1.016200e+02 +12 10671 3.859900e+02 -3.787100e+02 +18 10671 5.461899e+02 1.063700e+02 +12 10672 3.927000e+02 -3.776700e+02 +18 10672 5.521201e+02 1.073401e+02 +12 10673 3.927000e+02 -3.776700e+02 +18 10673 5.521201e+02 1.073401e+02 +12 10674 7.460500e+02 -3.772200e+02 +18 10674 8.850300e+02 1.048201e+02 +12 10675 5.467500e+02 -3.762700e+02 +18 10675 7.381499e+02 1.078201e+02 +12 10676 7.590701e+02 -3.762300e+02 +18 10676 8.615500e+02 1.043900e+02 +12 10677 8.119099e+02 -3.743000e+02 +18 10677 9.060200e+02 1.051799e+02 +12 10678 5.111200e+02 -3.712000e+02 +18 10678 6.541201e+02 1.114800e+02 +20 10678 5.640100e+02 -9.593994e+01 +12 10679 2.392100e+02 -3.647300e+02 +18 10679 3.659900e+02 1.195000e+02 +12 10680 5.661499e+02 -3.566899e+02 +18 10680 7.005200e+02 1.218401e+02 +20 10680 6.030801e+02 -8.653003e+01 +12 10681 6.563701e+02 -3.531600e+02 +18 10681 7.763401e+02 1.240500e+02 +12 10682 7.700195e-01 -3.342000e+02 +13 10682 1.619150e+03 1.055710e+03 +12 10683 2.420200e+02 -3.287800e+02 +18 10683 3.687100e+02 1.475601e+02 +12 10684 9.405601e+02 -3.069600e+02 +18 10684 1.016590e+03 1.579600e+02 +12 10685 9.853799e+02 -3.053000e+02 +18 10685 1.054660e+03 1.588000e+02 +12 10686 1.071420e+03 -3.023800e+02 +20 10686 9.601201e+02 -5.122998e+01 +12 10687 1.017340e+03 -2.967800e+02 +20 10687 9.223000e+02 -4.695996e+01 +12 10688 1.065780e+03 -2.947800e+02 +20 10688 1.041650e+03 -4.342004e+01 +12 10689 9.629099e+02 -2.889700e+02 +18 10689 1.036520e+03 1.717500e+02 +12 10690 2.511300e+02 -2.881700e+02 +20 10690 3.251100e+02 -3.651001e+01 +12 10691 -1.768800e+02 -2.873800e+02 +18 10691 4.834998e+01 1.842700e+02 +20 10691 4.554004e+01 -3.695996e+01 +12 10692 -1.768800e+02 -2.873800e+02 +18 10692 4.834998e+01 1.842700e+02 +20 10692 4.554004e+01 -3.695996e+01 +12 10693 -1.811100e+02 -2.830500e+02 +20 10693 4.182996e+01 -3.465002e+01 +12 10694 9.531299e+02 -2.569301e+02 +18 10694 1.028880e+03 1.988700e+02 +12 10695 9.705801e+02 -2.560400e+02 +18 10695 1.043930e+03 1.992600e+02 +12 10696 6.880300e+02 -2.470100e+02 +18 10696 8.039800e+02 2.105200e+02 +12 10697 7.593401e+02 -2.438500e+02 +18 10697 8.644399e+02 2.118500e+02 +12 10698 9.364099e+02 -2.408800e+02 +18 10698 1.015570e+03 2.121899e+02 +20 10698 8.658401e+02 -8.150024e+00 +12 10699 6.640801e+02 -2.344600e+02 +18 10699 7.835400e+02 2.198301e+02 +12 10700 6.977900e+02 -2.227400e+02 +18 10700 8.059800e+02 2.306000e+02 +12 10701 1.120300e+03 -2.044100e+02 +20 10701 9.972000e+02 1.615997e+01 +12 10702 9.858799e+02 -1.993700e+02 +18 10702 1.059470e+03 2.456000e+02 +12 10703 1.070630e+03 -1.950500e+02 +20 10703 9.607000e+02 2.292999e+01 +12 10704 1.119200e+03 -1.931300e+02 +20 10704 9.838401e+02 2.376001e+01 +12 10705 1.146090e+03 -1.916100e+02 +20 10705 1.014830e+03 2.496997e+01 +12 10706 9.325300e+02 -1.894399e+02 +20 10706 8.635701e+02 2.771997e+01 +12 10707 -1.259410e+03 -1.694600e+02 +20 10707 -6.765000e+02 4.039001e+01 +12 10708 1.074520e+03 -1.613900e+02 +20 10708 9.626699e+02 4.654004e+01 +12 10709 1.148750e+03 -1.544600e+02 +20 10709 1.005690e+03 5.062000e+01 +12 10710 -3.757100e+02 5.648300e+02 +18 10710 8.260010e+00 8.882500e+02 +20 10710 1.338000e+01 5.527100e+02 +12 10711 -3.757100e+02 5.648300e+02 +18 10711 -7.891003e+01 8.890200e+02 +20 10711 -6.053003e+01 5.532800e+02 +12 10712 -4.812300e+02 5.666000e+02 +18 10712 -7.891003e+01 8.890200e+02 +12 10713 -4.444000e+02 8.849000e+02 +20 10713 -4.077002e+01 7.794100e+02 +12 10714 -7.628600e+02 -9.505699e+02 +20 10714 -1.654500e+02 -4.897600e+02 +12 10715 4.860699e+02 -7.154500e+02 +18 10715 6.259900e+02 -1.633800e+02 +20 10715 5.455300e+02 -3.313101e+02 +12 10716 -8.944700e+02 -7.099700e+02 +18 10716 -4.903300e+02 -1.472400e+02 +12 10717 1.514399e+02 -7.028500e+02 +18 10717 3.149600e+02 -1.490200e+02 +12 10718 1.492700e+02 -6.993800e+02 +18 10718 3.142600e+02 -1.462400e+02 +12 10719 6.102100e+02 -6.979600e+02 +18 10719 6.691201e+02 -1.499301e+02 +12 10720 6.011699e+02 -6.899800e+02 +18 10720 7.217600e+02 -1.452400e+02 +20 10720 6.261499e+02 -3.145400e+02 +12 10721 -9.228000e+02 -6.665100e+02 +18 10721 -5.119700e+02 -1.136400e+02 +12 10722 5.617000e+02 -6.567700e+02 +17 10722 1.339080e+03 1.406400e+02 +20 10722 5.986799e+02 -2.921700e+02 +12 10723 4.782500e+02 -6.523500e+02 +20 10723 5.399800e+02 -2.887600e+02 +12 10724 5.174800e+02 -6.460601e+02 +17 10724 1.227000e+03 1.652000e+02 +12 10725 5.790100e+02 -6.418900e+02 +18 10725 7.042200e+02 -1.060100e+02 +12 10726 4.679200e+02 -6.315200e+02 +17 10726 1.091850e+03 1.989800e+02 +18 10726 6.122600e+02 -9.665002e+01 +20 10726 5.328000e+02 -2.737300e+02 +12 10727 5.602200e+02 -6.284399e+02 +17 10727 1.340300e+03 2.097600e+02 +18 10727 6.890701e+02 -9.545996e+01 +20 10727 5.980300e+02 -2.721700e+02 +12 10728 5.923301e+02 -6.282300e+02 +17 10728 1.255980e+03 2.087900e+02 +18 10728 7.156101e+02 -9.577002e+01 +20 10728 6.210801e+02 -2.722700e+02 +12 10729 5.757300e+02 -6.244301e+02 +17 10729 1.379410e+03 2.200701e+02 +12 10730 5.754299e+02 -5.970601e+02 +17 10730 1.382620e+03 2.860601e+02 +18 10730 7.022200e+02 -7.092004e+01 +20 10730 6.085100e+02 -2.514700e+02 +12 10731 5.778601e+02 -5.896500e+02 +20 10731 6.104700e+02 -2.456200e+02 +12 10732 5.778601e+02 -5.896500e+02 +17 10732 1.388330e+03 3.037600e+02 +18 10732 7.052500e+02 -6.490002e+01 +12 10733 4.479301e+02 -5.888600e+02 +18 10733 5.956101e+02 -6.243005e+01 +12 10734 3.393005e+01 -5.857300e+02 +18 10734 2.333900e+02 -5.557996e+01 +12 10735 1.771500e+02 -5.804399e+02 +18 10735 3.380699e+02 -5.256006e+01 +12 10736 9.980701e+02 -5.728500e+02 +20 10736 9.055701e+02 -2.365400e+02 +12 10737 4.597300e+02 -5.656700e+02 +20 10737 5.262600e+02 -2.293600e+02 +12 10738 5.134301e+02 -5.624301e+02 +18 10738 6.520100e+02 -4.244995e+01 +12 10739 1.768600e+02 -5.625900e+02 +18 10739 3.380100e+02 -3.867004e+01 +12 10740 -1.997800e+02 -5.612900e+02 +18 10740 4.873999e+01 -3.391003e+01 +12 10741 9.794900e+02 -5.366400e+02 +20 10741 1.033280e+03 -2.106200e+02 +12 10742 2.488000e+01 -5.355000e+02 +18 10742 2.264500e+02 -1.568994e+01 +12 10743 4.650699e+02 -5.262100e+02 +17 10743 1.086400e+03 4.557700e+02 +12 10744 4.001500e+02 -5.247400e+02 +17 10744 9.063799e+02 4.566699e+02 +12 10745 3.936400e+02 -5.251899e+02 +17 10745 8.661499e+02 4.539399e+02 +12 10746 3.850300e+02 -5.252100e+02 +18 10746 5.436299e+02 -1.084998e+01 +12 10747 3.850300e+02 -5.252100e+02 +18 10747 5.436299e+02 -1.084998e+01 +20 10747 4.722300e+02 -2.005000e+02 +12 10748 1.177530e+03 -5.166000e+02 +20 10748 1.033080e+03 -1.990400e+02 +12 10749 -1.868005e+01 -5.044301e+02 +18 10749 1.921300e+02 9.180054e+00 +12 10750 1.076810e+03 -5.032700e+02 +20 10750 9.622800e+02 -1.894100e+02 +12 10751 1.176610e+03 -5.013700e+02 +20 10751 1.032680e+03 -1.896400e+02 +12 10752 1.176610e+03 -5.013700e+02 +20 10752 1.032680e+03 -1.896400e+02 +12 10753 1.043500e+02 -4.929100e+02 +18 10753 2.907200e+02 1.800000e+01 +12 10754 9.705005e+01 -4.929100e+02 +18 10754 2.838800e+02 1.813000e+01 +20 10754 2.498800e+02 -1.779000e+02 +12 10755 9.569500e+02 -4.713300e+02 +18 10755 1.025140e+03 2.421997e+01 +12 10756 9.502800e+02 -4.714800e+02 +20 10756 8.737000e+02 -1.670800e+02 +12 10757 4.788900e+02 -4.668400e+02 +17 10757 1.142850e+03 6.040300e+02 +18 10757 6.253799e+02 3.460999e+01 +12 10758 9.501101e+02 -4.652200e+02 +18 10758 1.019510e+03 2.950000e+01 +12 10759 1.189399e+02 -4.632400e+02 +18 10759 3.013300e+02 4.116003e+01 +12 10760 -1.334998e+01 -4.610000e+02 +20 10760 1.740601e+02 -1.558800e+02 +12 10761 9.760701e+02 -4.504500e+02 +18 10761 1.041610e+03 4.095996e+01 +12 10762 9.760701e+02 -4.504500e+02 +20 10762 8.918301e+02 -1.526100e+02 +12 10763 4.198300e+02 -4.488900e+02 +17 10763 9.668799e+02 6.462800e+02 +20 10763 4.985699e+02 -1.489399e+02 +12 10764 1.074130e+03 -4.478600e+02 +20 10764 9.612600e+02 -1.514600e+02 +12 10765 5.682800e+02 -4.476700e+02 +18 10765 7.003401e+02 4.877002e+01 +12 10766 1.185200e+02 -4.308900e+02 +18 10766 2.913000e+02 6.781006e+01 +12 10767 1.144000e+02 -4.266500e+02 +18 10767 2.879700e+02 7.040991e+01 +12 10768 1.144000e+02 -4.266500e+02 +18 10768 2.879700e+02 7.040991e+01 +12 10769 7.031001e+02 -4.090500e+02 +20 10769 6.996299e+02 -1.229900e+02 +12 10770 1.099360e+03 -4.076000e+02 +20 10770 9.793999e+02 -1.240400e+02 +12 10771 6.463401e+02 -3.996600e+02 +18 10771 7.670300e+02 8.652002e+01 +12 10772 6.433101e+02 -3.971200e+02 +18 10772 7.639800e+02 8.893994e+01 +12 10773 -1.027200e+02 -3.933400e+02 +20 10773 9.793005e+01 -1.093199e+02 +12 10774 6.471899e+02 -3.798900e+02 +18 10774 7.678101e+02 1.026000e+02 +12 10775 5.218500e+02 -3.740601e+02 +18 10775 6.629199e+02 1.089500e+02 +12 10776 1.135360e+03 -3.733101e+02 +20 10776 1.066490e+03 -9.835999e+01 +12 10777 1.186480e+03 -3.722700e+02 +20 10777 9.619199e+02 -1.015200e+02 +12 10778 -1.766400e+02 -3.701200e+02 +17 10778 -9.177100e+02 7.902800e+02 +12 10779 4.537600e+02 -3.683300e+02 +17 10779 1.066530e+03 8.480400e+02 +12 10780 5.649600e+02 -3.648700e+02 +18 10780 6.990400e+02 1.155400e+02 +20 10780 6.022000e+02 -9.143005e+01 +12 10781 5.504199e+02 -3.648900e+02 +18 10781 6.750100e+02 1.155500e+02 +20 10781 5.916799e+02 -9.147998e+01 +12 10782 6.376699e+02 -3.615200e+02 +18 10782 7.601499e+02 1.176400e+02 +12 10783 6.298999e+02 -3.617900e+02 +18 10783 7.536299e+02 1.174099e+02 +20 10783 6.480300e+02 -9.004004e+01 +12 10784 4.779900e+02 -3.592500e+02 +17 10784 1.141810e+03 8.731700e+02 +18 10784 6.276001e+02 1.206100e+02 +20 10784 5.410200e+02 -8.809998e+01 +12 10785 4.829700e+02 -3.589800e+02 +17 10785 1.156730e+03 8.738900e+02 +12 10786 2.349200e+02 -3.561200e+02 +18 10786 3.625699e+02 1.263201e+02 +12 10787 5.421100e+02 -3.556000e+02 +18 10787 6.804800e+02 1.231799e+02 +12 10788 5.912000e+02 -3.457500e+02 +18 10788 7.206799e+02 1.310200e+02 +12 10789 -6.520020e+00 -3.441801e+02 +13 10789 1.588930e+03 1.013600e+03 +12 10790 -5.193994e+01 -3.427500e+02 +18 10790 1.479900e+02 1.393101e+02 +12 10791 -8.019300e+02 -3.320500e+02 +20 10791 1.036670e+03 -6.588000e+01 +12 10792 1.025830e+03 -3.303700e+02 +20 10792 9.281001e+02 -7.030005e+01 +12 10793 -2.337000e+01 -3.241000e+02 +13 10793 1.522940e+03 1.095730e+03 +17 10793 -7.159399e+02 8.554399e+02 +12 10794 6.235500e+02 -3.156300e+02 +18 10794 7.488000e+02 1.547500e+02 +12 10795 9.577100e+02 -2.853800e+02 +18 10795 1.031770e+03 1.755200e+02 +12 10796 5.188600e+02 -2.849000e+02 +20 10796 5.654700e+02 -3.606995e+01 +12 10797 6.826299e+02 -2.846000e+02 +20 10797 6.851001e+02 -3.721997e+01 +12 10798 9.733999e+02 -2.836200e+02 +18 10798 1.045410e+03 1.772300e+02 +12 10799 9.532100e+02 -2.830000e+02 +18 10799 1.028330e+03 1.773700e+02 +12 10800 -2.075100e+02 -2.805100e+02 +17 10800 -1.171360e+03 9.805100e+02 +18 10800 2.262000e+01 1.895400e+02 +12 10801 9.297900e+02 -2.801100e+02 +18 10801 1.007660e+03 1.800701e+02 +12 10802 6.886101e+02 -2.424500e+02 +18 10802 8.046001e+02 2.140500e+02 +12 10803 8.413301e+02 -2.367700e+02 +18 10803 9.336299e+02 2.170100e+02 +12 10804 9.462600e+02 -2.130000e+02 +18 10804 1.025610e+03 2.348600e+02 +12 10805 1.072170e+03 -2.066700e+02 +20 10805 9.630901e+02 1.490997e+01 +12 10806 4.003900e+02 -1.822300e+02 +18 10806 5.616201e+02 2.651100e+02 +20 10806 4.827500e+02 3.509009e+01 +12 10807 -1.312470e+03 -1.714500e+02 +20 10807 -7.138600e+02 3.778003e+01 +12 10808 1.066490e+03 -1.620500e+02 +20 10808 9.564700e+02 4.608008e+01 +12 10809 1.153090e+03 -1.572900e+02 +20 10809 1.008720e+03 4.854004e+01 +12 10810 1.229930e+03 -1.223000e+02 +20 10810 1.074910e+03 7.329004e+01 +12 10811 -5.309400e+02 -6.980400e+02 +13 10811 2.784200e+02 1.212900e+02 +12 10812 5.179399e+02 -6.513199e+02 +17 10812 1.225200e+03 1.521500e+02 +12 10813 9.507000e+02 -5.032800e+02 +18 10813 1.017880e+03 -7.700195e-01 +12 10814 -1.143500e+02 -4.950800e+02 +17 10814 -6.788900e+02 4.899700e+02 +12 10815 1.603003e+01 -4.787800e+02 +18 10815 2.195300e+02 3.001001e+01 +12 10816 -2.415002e+01 -4.743000e+02 +17 10816 -4.899200e+02 5.321400e+02 +20 10816 1.673400e+02 -1.645500e+02 +12 10817 3.958400e+02 -4.595300e+02 +18 10817 5.544199e+02 4.115002e+01 +12 10818 -1.025400e+02 -4.560200e+02 +17 10818 -6.541600e+02 5.857100e+02 +12 10819 5.558701e+02 -4.438800e+02 +18 10819 6.898501e+02 5.328003e+01 +12 10820 -9.756995e+01 -4.316100e+02 +17 10820 -6.384500e+02 6.470100e+02 +12 10821 4.780699e+02 -3.755601e+02 +18 10821 6.269399e+02 1.086000e+02 +12 10822 4.359600e+02 -3.696700e+02 +17 10822 1.016250e+03 8.444100e+02 +12 10823 4.661500e+02 -3.685800e+02 +20 10823 5.317900e+02 -9.393005e+01 +12 10824 4.724000e+02 -3.606000e+02 +17 10824 1.123170e+03 8.663600e+02 +12 10825 -7.663300e+02 -3.527500e+02 +18 10825 -4.164100e+02 1.324900e+02 +12 10826 -5.569995e+01 -3.501400e+02 +18 10826 1.442200e+02 1.324199e+02 +12 10827 5.228800e+02 -2.921400e+02 +18 10827 6.610701e+02 1.746500e+02 +12 10828 4.059399e+02 -2.888900e+02 +18 10828 5.646399e+02 1.791699e+02 +12 10829 -5.342004e+01 -2.863400e+02 +18 10829 1.456400e+02 1.845400e+02 +12 10830 6.995100e+02 -2.448000e+02 +18 10830 8.136001e+02 2.118800e+02 +12 10831 6.852900e+02 -2.439399e+02 +18 10831 8.021299e+02 2.135200e+02 +12 10832 6.668799e+02 -1.911899e+02 +18 10832 7.153501e+02 2.603301e+02 +20 10832 6.094900e+02 3.150000e+01 +13 10833 -1.436260e+03 6.878000e+02 +20 10833 -3.483199e+02 -1.481700e+02 +13 10834 2.505200e+02 2.011300e+02 +18 10834 -1.050601e+02 -1.279200e+02 +20 10834 -7.687000e+01 -3.072700e+02 +13 10835 -1.339120e+03 5.560000e+02 +18 10835 -3.932600e+02 3.652002e+01 +20 10835 -3.327200e+02 -1.668700e+02 +13 10836 -1.184280e+03 6.106599e+02 +18 10836 -3.644200e+02 5.217993e+01 +20 10836 -3.080400e+02 -1.514700e+02 +13 10837 -1.590270e+03 -2.510900e+02 +18 10837 -4.385100e+02 -1.275200e+02 +13 10838 1.520020e+03 6.600500e+02 +18 10838 1.607000e+02 5.071997e+01 +13 10839 2.670400e+02 1.100800e+02 +18 10839 -1.036801e+02 -1.423000e+02 +13 10840 1.056510e+03 4.825901e+02 +17 10840 2.319900e+02 4.095000e+02 +13 10841 -7.906700e+02 -1.900024e+00 +16 10841 8.705400e+02 2.729800e+02 +13 10842 1.475830e+03 1.461599e+02 +17 10842 -5.749700e+02 2.767900e+02 +13 10843 1.672630e+03 4.057600e+02 +17 10843 -4.816200e+02 4.314500e+02 +13 10844 1.408470e+03 4.448000e+02 +17 10844 -6.178800e+02 4.552000e+02 +18 10844 1.386400e+02 8.219971e+00 +13 10845 1.328270e+03 8.172600e+02 +17 10845 -6.712100e+02 6.804900e+02 +13 10846 1.486120e+03 1.048830e+03 +17 10846 -7.375900e+02 8.275300e+02 +13 10847 1.291350e+03 1.065690e+03 +17 10847 -8.532100e+02 8.405400e+02 +13 10848 1.533770e+03 1.069650e+03 +17 10848 -7.091300e+02 8.393800e+02 +13 10849 1.696200e+03 1.132910e+03 +17 10849 -6.147300e+02 8.748900e+02 +13 10850 1.501200e+03 -1.471300e+02 +17 10850 -5.587800e+02 1.026801e+02 +13 10851 1.539240e+03 -1.151000e+02 +17 10851 -5.381000e+02 1.233400e+02 +13 10852 2.789700e+02 1.011801e+02 +17 10852 -2.167300e+02 1.701599e+02 +13 10853 1.689320e+03 1.274800e+02 +17 10853 -4.716000e+02 2.673700e+02 +13 10854 1.347940e+03 1.346000e+02 +17 10854 -6.527200e+02 2.694299e+02 +13 10855 1.230930e+03 1.365901e+02 +17 10855 -7.216300e+02 2.705701e+02 +13 10856 1.672550e+03 1.472800e+02 +17 10856 -4.796500e+02 2.791899e+02 +13 10857 1.199650e+03 1.505000e+02 +17 10857 -7.389100e+02 2.788700e+02 +13 10858 1.253320e+03 1.885701e+02 +17 10858 -7.077400e+02 3.015901e+02 +13 10859 1.374590e+03 5.141300e+02 +17 10859 -6.375500e+02 4.958800e+02 +13 10860 1.570020e+03 5.906100e+02 +17 10860 -5.442900e+02 5.422000e+02 +13 10861 1.632510e+03 5.947700e+02 +17 10861 -5.074800e+02 5.434099e+02 +13 10862 1.587840e+03 1.029100e+03 +17 10862 -6.771600e+02 8.144700e+02 +13 10863 1.268740e+03 1.057870e+03 +17 10863 -8.670700e+02 8.369700e+02 +13 10864 1.498720e+03 1.131740e+03 +17 10864 -7.309700e+02 8.775400e+02 +13 10865 1.501660e+03 -1.724500e+02 +17 10865 -5.578900e+02 8.748999e+01 +13 10866 1.085350e+03 -6.005859e-02 +17 10866 2.741600e+02 1.122000e+02 +13 10867 1.675510e+03 2.146100e+02 +17 10867 -4.789500e+02 3.183800e+02 +13 10868 1.622400e+03 2.146799e+02 +17 10868 -5.096200e+02 3.188700e+02 +13 10869 1.680170e+03 2.242000e+02 +17 10869 -4.759301e+02 3.246400e+02 +13 10870 1.352250e+03 4.336200e+02 +17 10870 -6.520601e+02 4.482100e+02 +13 10871 1.368130e+03 5.082100e+02 +17 10871 -6.416100e+02 4.929000e+02 +13 10872 1.408680e+03 7.120601e+02 +17 10872 -6.202800e+02 6.141500e+02 +13 10873 1.342980e+03 7.153600e+02 +17 10873 -6.601000e+02 6.174199e+02 +13 10874 1.380060e+03 8.694700e+02 +17 10874 -6.391400e+02 7.106300e+02 +13 10875 1.598040e+03 1.035250e+03 +17 10875 -6.709500e+02 8.180500e+02 +13 10876 1.261940e+03 1.062300e+03 +17 10876 -8.711300e+02 8.394200e+02 +13 10877 1.427140e+03 1.068290e+03 +17 10877 -7.723600e+02 8.403400e+02 +13 10878 1.407040e+03 1.079240e+03 +17 10878 -7.844600e+02 8.470200e+02 +13 10879 1.675340e+03 1.103780e+03 +17 10879 -6.272800e+02 8.581000e+02 +13 10880 1.594550e+03 1.125930e+03 +17 10880 -6.738500e+02 8.726899e+02 +13 10881 1.586860e+03 1.126190e+03 +17 10881 -6.787800e+02 8.726700e+02 +13 10882 1.514570e+03 -1.728101e+02 +17 10882 -5.510100e+02 8.759998e+01 +13 10883 1.494960e+03 -1.095601e+02 +17 10883 -5.620900e+02 1.248000e+02 +13 10884 1.663670e+03 1.411200e+02 +17 10884 -4.851500e+02 2.754099e+02 +13 10885 1.632700e+03 5.661500e+02 +17 10885 -5.491100e+02 5.290701e+02 +13 10886 1.354000e+03 6.625900e+02 +17 10886 -6.541600e+02 5.857100e+02 +13 10887 1.692040e+03 1.019480e+03 +17 10887 -6.163700e+02 8.070300e+02 +13 10888 1.447870e+03 1.021840e+03 +17 10888 -7.593000e+02 8.119600e+02 +13 10889 1.478980e+03 1.031110e+03 +17 10889 -7.415400e+02 8.170900e+02 +13 10890 1.467850e+03 1.031730e+03 +17 10890 -7.478600e+02 8.173300e+02 +13 10891 1.466980e+03 1.042060e+03 +17 10891 -7.486600e+02 8.237200e+02 +13 10892 1.496590e+03 1.046950e+03 +17 10892 -7.305300e+02 8.263400e+02 +13 10893 1.418770e+03 1.052850e+03 +17 10893 -7.769700e+02 8.310500e+02 +13 10894 1.686790e+03 1.053790e+03 +17 10894 -6.197200e+02 8.281600e+02 +13 10895 1.401640e+03 1.053940e+03 +17 10895 -7.868800e+02 8.320701e+02 +13 10896 1.414260e+03 1.063040e+03 +17 10896 -7.798200e+02 8.370601e+02 +13 10897 1.517080e+03 1.093270e+03 +17 10897 -7.183800e+02 8.540800e+02 +13 10898 1.431890e+03 1.110170e+03 +17 10898 -7.698100e+02 8.656300e+02 +13 10899 1.527220e+03 1.114770e+03 +17 10899 -7.140000e+02 8.667600e+02 +13 10900 1.526430e+03 1.125280e+03 +17 10900 -7.144000e+02 8.735000e+02 +13 10901 9.247900e+02 -2.040039e+00 +17 10901 1.821200e+02 1.098300e+02 +13 10902 4.784900e+02 -1.469971e+00 +17 10902 -8.071997e+01 1.071200e+02 +13 10903 1.350510e+03 2.309900e+02 +17 10903 -6.519100e+02 3.279900e+02 +13 10904 1.185860e+03 4.345601e+02 +17 10904 -7.506100e+02 4.499700e+02 +13 10905 1.678480e+03 5.651300e+02 +17 10905 -4.799500e+02 5.272100e+02 +13 10906 1.547560e+03 5.666899e+02 +17 10906 -5.563900e+02 5.288900e+02 +13 10907 1.677930e+03 6.117500e+02 +17 10907 -4.807100e+02 5.542000e+02 +13 10908 1.457040e+03 7.762700e+02 +17 10908 -5.904900e+02 6.534900e+02 +13 10909 1.616870e+03 1.035290e+03 +17 10909 -6.605900e+02 8.177600e+02 +13 10910 1.481980e+03 1.036400e+03 +17 10910 -7.393600e+02 8.202000e+02 +13 10911 1.615350e+03 1.040780e+03 +17 10911 -6.616000e+02 8.209000e+02 +13 10912 1.699170e+03 1.044580e+03 +17 10912 -6.124500e+02 8.221700e+02 +13 10913 1.532040e+03 1.051910e+03 +17 10913 -7.103000e+02 8.286500e+02 +13 10914 1.486660e+03 1.052510e+03 +17 10914 -7.371200e+02 8.299500e+02 +13 10915 1.239590e+03 1.060990e+03 +17 10915 -8.643500e+02 8.390900e+02 +13 10916 1.427670e+03 1.062850e+03 +17 10916 -7.723600e+02 8.371799e+02 +13 10917 1.430090e+03 1.074560e+03 +17 10917 -7.698700e+02 8.437200e+02 +13 10918 1.421680e+03 1.074290e+03 +17 10918 -7.756600e+02 8.442200e+02 +13 10919 1.437090e+03 1.084720e+03 +17 10919 -7.666100e+02 8.500300e+02 +13 10920 1.430260e+03 1.084750e+03 +17 10920 -7.706300e+02 8.501000e+02 +13 10921 1.516280e+03 1.099400e+03 +17 10921 -7.200300e+02 8.575500e+02 +13 10922 1.425030e+03 1.105740e+03 +17 10922 -7.739600e+02 8.630601e+02 +13 10923 1.521780e+03 1.130000e+03 +17 10923 -7.171100e+02 8.763101e+02 +13 10924 1.409960e+03 1.132620e+03 +17 10924 -7.829000e+02 8.795901e+02 +14 10925 7.089001e+01 2.078500e+02 +16 10925 -2.273800e+02 3.024299e+02 +14 10926 -4.089900e+02 4.802200e+02 +15 10926 3.381600e+02 4.338201e+02 +16 10926 -8.746300e+02 5.913400e+02 +19 10926 -1.791100e+02 6.792100e+02 +14 10927 -1.921100e+02 3.952000e+02 +16 10927 -5.967800e+02 4.964700e+02 +19 10927 2.453700e+02 5.462100e+02 +14 10928 -2.576100e+02 4.959800e+02 +16 10928 -6.856000e+02 6.172400e+02 +19 10928 1.081200e+02 7.419200e+02 +14 10929 -4.354300e+02 4.951300e+02 +15 10929 3.072400e+02 4.513800e+02 +16 10929 -9.128900e+02 6.101899e+02 +19 10929 -2.284700e+02 7.032800e+02 +14 10930 -2.868300e+02 1.775900e+02 +16 10930 -6.976300e+02 2.227600e+02 +14 10931 -2.971700e+02 2.449400e+02 +19 10931 4.254004e+01 2.185200e+02 +14 10932 6.510010e+00 2.535300e+02 +15 10932 8.882200e+02 1.879500e+02 +16 10932 -3.290000e+02 3.459700e+02 +19 10932 7.156699e+02 2.742200e+02 +14 10933 -1.948600e+02 3.330200e+02 +19 10933 2.436100e+02 4.163500e+02 +14 10934 -2.069000e+02 3.808700e+02 +19 10934 2.156100e+02 5.124600e+02 +14 10935 -2.566500e+02 4.212900e+02 +19 10935 1.134700e+02 5.890200e+02 +14 10936 1.131000e+01 4.325400e+02 +19 10936 7.141499e+02 6.723101e+02 +14 10937 -9.620001e+01 4.963700e+02 +16 10937 -4.839300e+02 6.313000e+02 +14 10938 -3.830600e+02 5.092700e+02 +15 10938 3.687900e+02 4.734700e+02 +16 10938 -8.450100e+02 6.300000e+02 +19 10938 -1.311700e+02 7.423400e+02 +14 10939 -1.155000e+02 5.370900e+02 +15 10939 6.987000e+02 5.401500e+02 +16 10939 -5.119000e+02 6.822000e+02 +19 10939 3.980699e+02 8.623101e+02 +14 10940 -2.455100e+02 6.090800e+02 +19 10940 1.314399e+02 9.739800e+02 +14 10941 -1.553500e+02 1.839600e+02 +15 10941 6.590601e+02 8.133002e+01 +16 10941 -5.308700e+02 2.395100e+02 +14 10942 -3.995999e+01 2.224200e+02 +16 10942 -3.885200e+02 2.982500e+02 +14 10943 -2.462400e+02 2.553300e+02 +19 10943 1.372700e+02 2.459399e+02 +14 10944 -2.462400e+02 2.553300e+02 +19 10944 1.372700e+02 2.459399e+02 +14 10945 7.279999e+00 2.713700e+02 +16 10945 -3.288300e+02 3.677500e+02 +19 10945 7.174600e+02 3.129900e+02 +14 10946 -5.414999e+01 3.606100e+02 +19 10946 5.564800e+02 4.981100e+02 +14 10947 3.493600e+02 3.715300e+02 +20 10947 -7.028000e+02 8.140015e+00 +14 10948 -2.452800e+02 3.852400e+02 +16 10948 -6.623900e+02 4.799700e+02 +19 10948 1.370699e+02 5.159800e+02 +14 10949 -3.863600e+02 5.252000e+02 +19 10949 -1.362800e+02 7.736000e+02 +14 10950 -3.156200e+02 1.540300e+02 +15 10950 4.558900e+02 4.045001e+01 +16 10950 -7.295500e+02 1.927500e+02 +14 10951 -2.424800e+02 2.192600e+02 +15 10951 5.459200e+02 1.226800e+02 +14 10952 -2.424800e+02 2.192600e+02 +15 10952 5.459200e+02 1.226800e+02 +14 10953 -1.739990e+00 2.395900e+02 +15 10953 8.759399e+02 1.688200e+02 +14 10954 1.964500e+02 2.867700e+02 +16 10954 -4.669000e+01 4.256300e+02 +19 10954 1.249280e+03 3.846200e+02 +14 10955 -2.399400e+02 3.101000e+02 +19 10955 1.513000e+02 3.608700e+02 +14 10956 -2.587000e+02 3.115500e+02 +15 10956 5.239301e+02 2.371900e+02 +14 10957 1.869500e+02 3.134600e+02 +19 10957 1.224780e+03 4.417800e+02 +14 10958 2.130300e+02 3.277700e+02 +16 10958 -2.846002e+01 4.794399e+02 +14 10959 -1.083100e+02 3.690500e+02 +19 10959 4.299200e+02 5.059299e+02 +14 10960 -4.621600e+02 4.766300e+02 +15 10960 2.764100e+02 4.269399e+02 +19 10960 -2.756000e+02 6.614600e+02 +14 10961 -1.135000e+02 5.078500e+02 +16 10961 -5.063400e+02 6.435601e+02 +14 10962 -1.220500e+02 2.038800e+02 +16 10962 -4.920100e+02 2.680200e+02 +14 10963 3.357200e+02 3.825500e+02 +18 10963 -8.452500e+02 2.589900e+02 +14 10964 -1.950600e+02 4.017500e+02 +19 10964 2.389000e+02 5.585601e+02 +14 10965 -3.281100e+02 5.399000e+02 +19 10965 -2.557996e+01 8.157400e+02 +14 10966 -2.000100e+02 5.471300e+02 +19 10966 2.199500e+02 8.596700e+02 +14 10967 -3.219600e+02 1.756700e+02 +16 10967 -7.376900e+02 2.186800e+02 +14 10968 -1.750100e+02 2.653600e+02 +15 10968 6.320300e+02 1.846800e+02 +14 10969 -3.007700e+02 2.720500e+02 +19 10969 3.408997e+01 2.744399e+02 +14 10970 8.401001e+01 3.511500e+02 +16 10970 -1.733800e+02 5.260701e+02 +14 10971 -8.053000e+01 3.932700e+02 +16 10971 -4.554600e+02 5.050400e+02 +14 10972 -3.529300e+02 4.940200e+02 +19 10972 -7.420996e+01 7.182000e+02 +14 10973 -1.974100e+02 5.361500e+02 +16 10973 -6.149200e+02 6.716899e+02 +19 10973 2.261400e+02 8.392800e+02 +14 10974 -1.353700e+02 5.378800e+02 +19 10974 3.578900e+02 8.581200e+02 +14 10975 -1.666400e+02 5.406100e+02 +16 10975 -5.751900e+02 6.811899e+02 +14 10976 -1.864200e+02 5.757200e+02 +15 10976 6.144000e+02 5.850400e+02 +16 10976 -5.980400e+02 7.308700e+02 +14 10977 -2.930600e+02 1.309300e+02 +15 10977 4.847400e+02 1.247998e+01 +14 10978 -2.822900e+02 1.615300e+02 +16 10978 -6.883500e+02 2.042200e+02 +14 10979 -7.210001e+01 1.643000e+02 +16 10979 -4.301200e+02 2.240700e+02 +14 10980 -6.812000e+01 1.740500e+02 +15 10980 7.792800e+02 7.359003e+01 +14 10981 -8.070001e+01 1.748700e+02 +15 10981 7.604200e+02 7.401001e+01 +14 10982 -1.674300e+02 1.899200e+02 +15 10982 6.424900e+02 8.888000e+01 +14 10983 -2.293800e+02 1.980300e+02 +19 10983 1.802900e+02 1.276599e+02 +14 10984 -8.880005e+00 2.195900e+02 +15 10984 8.656801e+02 1.409600e+02 +14 10985 1.180100e+02 2.404900e+02 +20 10985 -1.051590e+03 -1.272100e+02 +14 10986 -2.336000e+02 2.605000e+02 +15 10986 5.570800e+02 1.749700e+02 +19 10986 1.676899e+02 2.581300e+02 +14 10987 -2.067900e+02 2.874600e+02 +19 10987 2.194301e+02 3.180200e+02 +14 10988 -5.320001e+01 2.900800e+02 +16 10988 -4.107700e+02 3.812600e+02 +14 10989 2.195900e+02 3.099500e+02 +16 10989 -2.328003e+01 4.547600e+02 +14 10990 9.190002e+00 3.107300e+02 +15 10990 8.912500e+02 2.670500e+02 +16 10990 -3.279300e+02 4.176600e+02 +19 10990 7.209199e+02 4.006599e+02 +14 10991 2.928600e+02 3.253500e+02 +16 10991 5.981995e+01 4.726400e+02 +18 10991 -9.068900e+02 1.822800e+02 +14 10992 -7.290009e+00 3.344300e+02 +15 10992 8.600100e+02 2.964800e+02 +16 10992 -3.549600e+02 4.446100e+02 +19 10992 6.707700e+02 4.520400e+02 +14 10993 -5.512000e+01 3.414900e+02 +19 10993 5.529900e+02 4.567300e+02 +14 10994 1.805500e+02 3.541700e+02 +19 10994 1.216280e+03 5.374800e+02 +14 10995 -9.710999e+01 3.675800e+02 +15 10995 7.321200e+02 3.225100e+02 +14 10996 3.950000e+01 4.144500e+02 +16 10996 -2.866100e+02 5.628600e+02 +19 10996 8.117300e+02 6.399100e+02 +14 10997 -1.384200e+02 4.511000e+02 +15 10997 6.738300e+02 4.238400e+02 +16 10997 -5.334400e+02 5.700300e+02 +14 10998 -2.943900e+02 4.590100e+02 +16 10998 -7.287500e+02 5.697600e+02 +19 10998 3.843005e+01 6.588400e+02 +14 10999 -4.122700e+02 4.898600e+02 +15 10999 3.347200e+02 4.468900e+02 +16 10999 -8.818600e+02 6.046799e+02 +19 10999 -1.860000e+02 6.975701e+02 +14 11000 -2.682300e+02 4.912200e+02 +15 11000 5.076400e+02 4.602500e+02 +14 11001 -2.422000e+02 4.913400e+02 +19 11001 1.376100e+02 7.353201e+02 +14 11002 -3.740500e+02 5.021799e+02 +19 11002 -1.150200e+02 7.298600e+02 +14 11003 -7.656000e+01 5.345400e+02 +16 11003 -4.601300e+02 6.854301e+02 +14 11004 -1.242900e+02 5.378000e+02 +19 11004 3.801700e+02 8.600000e+02 +14 11005 -8.100006e+00 5.433000e+02 +19 11005 6.918301e+02 9.108000e+02 +14 11006 -2.014900e+02 5.576000e+02 +16 11006 -6.210400e+02 6.990699e+02 +14 11007 -2.012800e+02 5.678500e+02 +15 11007 5.914399e+02 5.728000e+02 +14 11008 -2.210200e+02 5.799600e+02 +19 11008 1.804900e+02 9.228101e+02 +14 11009 -3.232000e+02 1.549800e+02 +16 11009 -7.384300e+02 1.934600e+02 +14 11010 -2.238400e+02 1.779200e+02 +15 11010 5.700800e+02 7.138000e+01 +14 11011 -3.075700e+02 1.932400e+02 +15 11011 4.641700e+02 8.904999e+01 +14 11012 -3.100700e+02 1.957700e+02 +15 11012 4.611000e+02 9.228003e+01 +14 11013 -3.042700e+02 1.986400e+02 +15 11013 4.722800e+02 9.708002e+01 +14 11014 -2.749700e+02 2.011000e+02 +15 11014 5.067300e+02 9.916998e+01 +14 11015 -2.131000e+01 2.042400e+02 +15 11015 8.462500e+02 1.179800e+02 +14 11016 1.211100e+02 2.085800e+02 +19 11016 1.057330e+03 1.864800e+02 +14 11017 4.540009e+00 2.238500e+02 +19 11017 7.163899e+02 2.072000e+02 +14 11018 -2.038800e+02 2.252700e+02 +15 11018 5.942900e+02 1.320200e+02 +14 11019 -3.164300e+02 2.344600e+02 +19 11019 6.290039e+00 1.952200e+02 +14 11020 9.734003e+01 2.431200e+02 +16 11020 -1.601300e+02 3.677700e+02 +19 11020 1.043200e+03 2.637300e+02 +14 11021 9.734003e+01 2.431200e+02 +16 11021 -1.601300e+02 3.677700e+02 +14 11022 -2.368700e+02 2.475300e+02 +15 11022 5.530100e+02 1.587000e+02 +14 11023 -1.240800e+02 2.546500e+02 +16 11023 -4.989900e+02 3.291300e+02 +14 11024 -1.937800e+02 2.586900e+02 +19 11024 2.487700e+02 2.592600e+02 +14 11025 -1.839600e+02 2.621000e+02 +19 11025 2.713199e+02 2.673201e+02 +14 11026 -2.753200e+02 2.620700e+02 +16 11026 -6.882900e+02 3.266100e+02 +19 11026 8.128003e+01 2.567700e+02 +14 11027 -1.720000e+02 2.681200e+02 +19 11027 2.959000e+02 2.814600e+02 +14 11028 9.328998e+01 2.699800e+02 +19 11028 1.032720e+03 3.244900e+02 +14 11029 -2.585600e+02 2.719500e+02 +16 11029 -6.682800e+02 3.395701e+02 +14 11030 1.719900e+02 2.771300e+02 +16 11030 -7.371002e+01 4.126200e+02 +14 11031 7.208002e+01 2.889000e+02 +16 11031 -1.945800e+02 4.312600e+02 +19 11031 9.875200e+02 3.636599e+02 +14 11032 -2.030900e+02 2.904200e+02 +15 11032 5.945500e+02 2.139500e+02 +14 11033 -2.482300e+02 2.930200e+02 +15 11033 5.373199e+02 2.145700e+02 +14 11034 9.515997e+01 3.074700e+02 +19 11034 1.034690e+03 4.113700e+02 +14 11035 1.836700e+02 3.091600e+02 +19 11035 1.221270e+03 4.300100e+02 +14 11036 1.908900e+02 3.113400e+02 +19 11036 1.234370e+03 4.381699e+02 +14 11037 2.891400e+02 3.216500e+02 +18 11037 -9.123500e+02 1.775701e+02 +20 11037 -7.814800e+02 -4.640002e+01 +14 11038 1.426300e+02 3.233000e+02 +16 11038 -1.119100e+02 4.753101e+02 +14 11039 -2.608000e+02 3.270000e+02 +15 11039 5.210000e+02 2.559299e+02 +14 11040 1.380000e+02 3.601800e+02 +16 11040 -1.202200e+02 5.277800e+02 +19 11040 1.119080e+03 5.407400e+02 +14 11041 2.305900e+02 3.723900e+02 +19 11041 1.343410e+03 5.930701e+02 +14 11042 -2.089600e+02 3.983600e+02 +15 11042 5.839700e+02 3.492100e+02 +14 11043 3.699300e+02 3.992300e+02 +16 11043 1.448500e+02 5.695900e+02 +14 11044 -3.019400e+02 4.903800e+02 +15 11044 4.666200e+02 4.566899e+02 +19 11044 2.243005e+01 7.213300e+02 +14 11045 -3.921800e+02 4.902500e+02 +15 11045 3.586400e+02 4.490701e+02 +14 11046 -3.800000e+02 5.046600e+02 +19 11046 -1.262800e+02 7.335701e+02 +14 11047 -3.360900e+02 5.060200e+02 +19 11047 -8.932996e+01 7.403700e+02 +14 11048 -2.294000e+01 5.079000e+02 +16 11048 -3.875600e+02 6.585100e+02 +14 11049 -2.484800e+02 5.122900e+02 +15 11049 5.315800e+02 4.889500e+02 +19 11049 1.253600e+02 7.770601e+02 +14 11050 -3.001800e+02 5.236899e+02 +15 11050 4.671700e+02 4.972500e+02 +16 11050 -7.421100e+02 6.502100e+02 +14 11051 -1.096400e+02 5.346801e+02 +16 11051 -5.032900e+02 6.798800e+02 +14 11052 -1.242400e+02 5.612900e+02 +16 11052 -5.251600e+02 7.209200e+02 +14 11053 -2.533000e+02 5.797600e+02 +15 11053 5.230500e+02 5.702000e+02 +16 11053 -6.882700e+02 7.216300e+02 +19 11053 1.119000e+02 9.129900e+02 +15 11054 4.638500e+02 2.009700e+02 +16 11054 -7.291600e+02 3.516899e+02 +15 11055 4.916200e+02 3.489000e+02 +16 11055 -7.125400e+02 4.988600e+02 +19 11055 6.097998e+01 5.434199e+02 +15 11056 6.402800e+02 4.298800e+02 +16 11056 -5.649900e+02 5.767300e+02 +15 11057 8.899900e+02 1.553600e+02 +16 11057 -3.242600e+02 3.142900e+02 +15 11058 4.197900e+02 1.677100e+02 +16 11058 -7.646100e+02 3.191799e+02 +15 11059 2.776600e+02 3.401100e+02 +16 11059 -9.361000e+02 4.959399e+02 +15 11060 5.252900e+02 4.345800e+02 +16 11060 -6.790700e+02 5.847500e+02 +15 11061 6.542100e+02 5.149900e+02 +16 11061 -5.565700e+02 6.594800e+02 +15 11062 2.979900e+02 3.124200e+02 +16 11062 -9.132600e+02 4.648700e+02 +15 11063 4.614399e+02 3.206899e+02 +16 11063 -7.391600e+02 4.718201e+02 +19 11063 1.677002e+01 4.967300e+02 +15 11064 3.387600e+02 4.111400e+02 +16 11064 -8.728600e+02 5.673201e+02 +19 11064 -1.773300e+02 6.396400e+02 +15 11065 4.797000e+02 6.320007e+00 +16 11065 -7.037600e+02 1.589700e+02 +15 11066 5.196100e+02 1.484800e+02 +19 11066 1.122000e+02 2.127100e+02 +15 11067 5.393199e+02 1.678900e+02 +16 11067 -6.530300e+02 3.196799e+02 +15 11068 5.393199e+02 1.678900e+02 +16 11068 -6.530300e+02 3.196799e+02 +15 11069 4.903500e+02 4.231600e+02 +16 11069 -7.142000e+02 5.743300e+02 +15 11070 4.546000e+02 8.315002e+01 +16 11070 -7.333200e+02 2.348900e+02 +15 11071 8.797100e+02 1.507700e+02 +16 11071 -3.335900e+02 3.098000e+02 +19 11071 7.055500e+02 2.113500e+02 +15 11072 8.530800e+02 1.516500e+02 +19 11072 6.593000e+02 2.150701e+02 +15 11073 -2.279900e+02 4.585500e+02 +19 11073 -1.037330e+03 6.835300e+02 +15 11074 4.560400e+02 2.934003e+01 +16 11074 -7.286800e+02 1.817300e+02 +15 11075 4.485699e+02 4.742999e+01 +16 11075 -7.381200e+02 1.989400e+02 +15 11076 8.978900e+02 1.748000e+02 +19 11076 7.303000e+02 2.505601e+02 +15 11077 7.382100e+02 2.634600e+02 +19 11077 4.652300e+02 4.049700e+02 +15 11078 2.404700e+02 4.995100e+02 +19 11078 -3.260100e+02 7.755200e+02 +15 11079 5.720601e+02 6.262000e+01 +19 11079 1.940400e+02 6.952002e+01 +15 11080 8.965300e+02 2.569600e+02 +19 11080 7.298101e+02 3.826300e+02 +15 11081 6.902000e+02 2.578500e+02 +16 11081 -5.116500e+02 4.090900e+02 +15 11082 5.852900e+02 2.819500e+02 +16 11082 -6.140200e+02 4.326000e+02 +15 11083 5.852900e+02 2.819500e+02 +16 11083 -6.140200e+02 4.326000e+02 +15 11084 9.073500e+02 3.355601e+02 +19 11084 7.468799e+02 5.060300e+02 +15 11085 9.016000e+02 3.442300e+02 +16 11085 -3.205800e+02 4.877400e+02 +19 11085 7.379399e+02 5.230400e+02 +15 11086 3.707800e+02 3.491000e+02 +16 11086 -8.370500e+02 5.013700e+02 +19 11086 -1.289399e+02 5.381799e+02 +15 11087 6.226400e+02 4.965200e+02 +16 11087 -5.861700e+02 6.427900e+02 +15 11088 3.172500e+02 3.260010e+00 +16 11088 -8.705400e+02 1.494300e+02 +15 11089 4.646500e+02 4.062000e+01 +16 11089 -7.209800e+02 1.934900e+02 +15 11090 5.149100e+02 4.390002e+01 +16 11090 -6.693500e+02 1.986000e+02 +15 11091 5.237100e+02 4.556000e+01 +16 11091 -6.622900e+02 2.006200e+02 +15 11092 3.941400e+02 5.565997e+01 +16 11092 -7.815200e+02 2.056600e+02 +15 11093 4.575601e+02 6.264001e+01 +16 11093 -7.286700e+02 2.148500e+02 +15 11094 4.608101e+02 1.086100e+02 +16 11094 -7.277700e+02 2.602400e+02 +15 11095 4.604700e+02 1.234900e+02 +16 11095 -7.287500e+02 2.744000e+02 +15 11096 5.696899e+02 1.724700e+02 +16 11096 -6.246300e+02 3.251000e+02 +15 11097 6.319000e+02 2.397800e+02 +16 11097 -5.654200e+02 3.915701e+02 +15 11098 9.012300e+02 2.709900e+02 +19 11098 7.382700e+02 4.039600e+02 +15 11099 9.060200e+02 2.780200e+02 +16 11099 -3.154700e+02 4.273000e+02 +19 11099 7.467100e+02 4.119800e+02 +15 11100 4.571400e+02 2.927700e+02 +16 11100 -7.433800e+02 4.436300e+02 +15 11101 5.231899e+02 4.545000e+02 +16 11101 -6.829200e+02 6.048201e+02 +19 11101 1.119000e+02 7.227900e+02 +15 11102 4.859000e+02 4.937000e+02 +16 11102 -7.224800e+02 6.454200e+02 +15 11103 5.752800e+02 6.581200e+02 +19 11103 1.988700e+02 1.053790e+03 +15 11104 3.838199e+02 5.154999e+01 +16 11104 -7.926000e+02 2.027000e+02 +15 11105 5.953700e+02 5.878003e+01 +19 11105 2.315400e+02 6.403003e+01 +15 11106 4.641600e+02 6.183002e+01 +16 11106 -7.225600e+02 2.135500e+02 +15 11107 4.580200e+02 7.133002e+01 +16 11107 -7.292700e+02 2.230800e+02 +15 11108 4.251801e+02 9.160999e+01 +19 11108 -4.069995e+01 1.125801e+02 +15 11109 5.283300e+02 9.326001e+01 +19 11109 1.218199e+02 1.208500e+02 +15 11110 4.545800e+02 9.792999e+01 +16 11110 -7.337700e+02 2.495400e+02 +15 11111 8.849399e+02 1.036700e+02 +16 11111 -3.279800e+02 2.660100e+02 +15 11112 8.325900e+02 1.078800e+02 +16 11112 -3.737700e+02 2.698101e+02 +15 11113 4.647700e+02 1.119200e+02 +16 11113 -7.244200e+02 2.636400e+02 +15 11114 4.610800e+02 1.463900e+02 +19 11114 1.431995e+01 2.058401e+02 +15 11115 8.849000e+02 1.608900e+02 +16 11115 -3.288100e+02 3.191600e+02 +15 11116 4.890900e+02 1.701900e+02 +16 11116 -7.054600e+02 3.214299e+02 +15 11117 8.167000e+02 1.706200e+02 +19 11117 5.955601e+02 2.494000e+02 +15 11118 9.016300e+02 1.734300e+02 +19 11118 7.415601e+02 2.450801e+02 +15 11119 5.966801e+02 1.849900e+02 +19 11119 2.305200e+02 2.766400e+02 +15 11120 8.364000e+02 2.242700e+02 +19 11120 6.297900e+02 3.364099e+02 +15 11121 4.653500e+02 2.473200e+02 +19 11121 2.027002e+01 3.740100e+02 +15 11122 5.446200e+02 3.162800e+02 +19 11122 1.459800e+02 4.934000e+02 +15 11123 8.506700e+02 3.265701e+02 +19 11123 6.509099e+02 5.043301e+02 +15 11124 5.807000e+02 3.460500e+02 +16 11124 -6.206000e+02 4.955200e+02 +15 11125 4.020699e+02 3.635800e+02 +19 11125 -7.912000e+01 5.641400e+02 +15 11126 3.881801e+02 3.945601e+02 +19 11126 -1.043300e+02 6.165200e+02 +15 11127 6.659900e+02 4.162900e+02 +16 11127 -5.402100e+02 5.621300e+02 +15 11128 8.648700e+02 4.479800e+02 +19 11128 6.741899e+02 7.011700e+02 +15 11129 8.648700e+02 4.479800e+02 +19 11129 6.741899e+02 7.011700e+02 +15 11130 7.678101e+02 4.618500e+02 +19 11130 5.107000e+02 7.339500e+02 +15 11131 -2.065100e+02 4.809600e+02 +19 11131 -1.002940e+03 7.165200e+02 +15 11132 -1.731500e+02 4.845400e+02 +19 11132 -9.467500e+02 7.213300e+02 +15 11133 6.348500e+02 5.089399e+02 +16 11133 -5.745200e+02 6.534800e+02 +15 11134 -3.172100e+02 5.147700e+02 +19 11134 -1.386850e+03 8.841200e+02 +15 11135 5.920000e+02 5.262300e+02 +16 11135 -6.171500e+02 6.734399e+02 +15 11136 5.699700e+02 5.303600e+02 +19 11136 1.866000e+02 8.493800e+02 +15 11137 4.912500e+02 5.482900e+02 +16 11137 -7.212800e+02 7.015200e+02 +19 11137 6.291003e+01 8.754000e+02 +15 11138 6.876700e+02 5.794800e+02 +19 11138 3.796500e+02 9.141000e+02 +15 11139 3.132900e+02 4.250000e+00 +16 11139 -8.744900e+02 1.497200e+02 +15 11140 6.321899e+02 9.535999e+01 +16 11140 -5.592900e+02 2.524200e+02 +15 11141 4.968500e+02 1.001200e+02 +19 11141 7.251001e+01 1.310901e+02 +15 11142 4.541700e+02 1.075600e+02 +16 11142 -7.349400e+02 2.589200e+02 +15 11143 4.646000e+02 1.154500e+02 +16 11143 -7.245300e+02 2.668700e+02 +15 11144 4.912900e+02 1.423600e+02 +19 11144 6.413000e+01 2.009900e+02 +15 11145 8.721000e+02 1.490500e+02 +19 11145 6.913501e+02 2.095500e+02 +15 11146 5.464500e+02 1.659700e+02 +16 11146 -6.471100e+02 3.185000e+02 +15 11147 4.975699e+02 1.872700e+02 +19 11147 7.151001e+01 2.758800e+02 +15 11148 8.474399e+02 2.200700e+02 +19 11148 6.484800e+02 3.298800e+02 +15 11149 5.546500e+02 2.584700e+02 +19 11149 1.625100e+02 3.971200e+02 +15 11150 5.356200e+02 2.590800e+02 +19 11150 1.313700e+02 3.986400e+02 +15 11151 8.499301e+02 3.183900e+02 +19 11151 6.506699e+02 4.898201e+02 +15 11152 4.424600e+02 3.290900e+02 +16 11152 -7.603200e+02 4.802100e+02 +15 11153 7.566400e+02 3.311400e+02 +16 11153 -4.524400e+02 4.785900e+02 +15 11154 7.616100e+02 3.728500e+02 +19 11154 5.022700e+02 5.872800e+02 +15 11155 3.250400e+02 3.782400e+02 +19 11155 -2.009600e+02 5.841700e+02 +15 11156 8.507900e+02 3.968300e+02 +19 11156 6.527000e+02 6.217300e+02 +15 11157 3.977400e+02 4.062400e+02 +16 11157 -8.119900e+02 5.596100e+02 +15 11158 5.952500e+02 4.635200e+02 +19 11158 2.266400e+02 7.403300e+02 +15 11159 2.269399e+02 4.688400e+02 +19 11159 -3.538800e+02 7.279299e+02 +15 11160 7.813101e+02 4.918700e+02 +19 11160 5.341000e+02 7.817200e+02 +15 11161 4.591500e+02 5.106000e+02 +16 11161 -7.514100e+02 6.648700e+02 +15 11162 4.687600e+02 5.193000e+02 +19 11162 2.747998e+01 8.235400e+02 +15 11163 5.023199e+02 5.381300e+02 +19 11163 7.940002e+01 8.581400e+02 +15 11164 5.814301e+02 5.393700e+02 +16 11164 -6.280500e+02 6.876100e+02 +19 11164 2.077700e+02 8.628400e+02 +15 11165 5.424500e+02 5.529299e+02 +19 11165 1.425000e+02 8.851600e+02 +15 11166 6.750000e+02 5.574299e+02 +19 11166 3.607500e+02 8.900100e+02 +15 11167 1.234399e+02 5.636600e+02 +19 11167 -4.807400e+02 8.543000e+02 +16 11168 -4.017999e+01 5.280701e+02 +19 11168 1.264230e+03 5.585900e+02 +16 11169 -1.660200e+02 4.163201e+02 +19 11169 1.035710e+03 3.466400e+02 +16 11170 -3.480600e+02 4.010200e+02 +19 11170 6.827200e+02 3.765601e+02 +16 11171 -7.048600e+02 3.172600e+02 +19 11171 5.628003e+01 2.395901e+02 +16 11172 -7.048600e+02 3.172600e+02 +19 11172 5.628003e+01 2.395901e+02 +16 11173 -4.421400e+02 3.005000e+02 +19 11173 5.015800e+02 2.062000e+02 +16 11174 -1.834300e+02 3.626000e+02 +19 11174 1.003710e+03 2.510300e+02 +16 11175 -5.640200e+02 4.649399e+02 +19 11175 2.997400e+02 4.941200e+02 +16 11176 -3.588300e+02 6.110200e+02 +19 11176 6.712000e+02 7.409900e+02 +16 11177 -6.818600e+02 3.097700e+02 +19 11177 8.948999e+01 2.287300e+02 +16 11178 -1.941500e+02 3.920400e+02 +19 11178 9.865200e+02 2.988700e+02 +16 11179 -2.256700e+02 4.148900e+02 +19 11179 9.336499e+02 3.322000e+02 +16 11180 -2.246100e+02 4.493400e+02 +19 11180 9.720701e+02 4.021699e+02 +16 11181 -4.531200e+02 5.141799e+02 +19 11181 4.940699e+02 5.786300e+02 +16 11182 -7.555100e+02 5.406200e+02 +19 11182 -6.199951e+00 6.092300e+02 +16 11183 -1.736700e+02 3.649600e+02 +19 11183 1.019940e+03 2.585601e+02 +16 11184 -7.285700e+02 4.109600e+02 +19 11184 2.690002e+01 3.961799e+02 +16 11185 -4.669000e+01 4.256300e+02 +19 11185 1.249280e+03 3.846200e+02 +16 11186 -2.335100e+02 4.503600e+02 +19 11186 9.228501e+02 3.885500e+02 +16 11187 -2.335100e+02 4.503600e+02 +19 11187 9.228501e+02 3.885500e+02 +16 11188 -2.142000e+02 4.555300e+02 +19 11188 9.545801e+02 4.008000e+02 +16 11189 -2.373400e+02 5.033300e+02 +19 11189 9.195701e+02 4.697800e+02 +16 11190 -7.459998e+01 5.541100e+02 +19 11190 1.200600e+03 5.955000e+02 +16 11191 -7.292100e+02 5.599900e+02 +19 11191 3.606006e+01 6.434000e+02 +16 11192 -8.673900e+02 5.792400e+02 +19 11192 -1.678000e+02 6.587800e+02 +16 11193 -6.091800e+02 7.185699e+02 +19 11193 2.466100e+02 9.024500e+02 +16 11194 -6.717400e+02 2.297800e+02 +19 11194 9.956995e+01 9.137000e+01 +16 11195 -3.413200e+02 4.352800e+02 +19 11195 6.971101e+02 4.328700e+02 +16 11196 -2.133700e+02 4.718800e+02 +19 11196 9.581001e+02 4.268800e+02 +16 11197 -1.936000e+02 4.775800e+02 +19 11197 9.906499e+02 4.399500e+02 +16 11198 -6.925000e+01 5.660900e+02 +20 11198 -9.610600e+02 7.359998e+01 +16 11199 -3.104400e+02 3.298700e+02 +19 11199 7.511799e+02 2.412000e+02 +16 11200 9.977100e+02 3.732800e+02 +17 11200 -8.608000e+02 4.977000e+02 +18 11200 5.893994e+01 2.005005e+01 +16 11201 -2.430400e+02 4.096000e+02 +19 11201 9.070200e+02 3.202300e+02 +16 11202 -4.703998e+01 4.176400e+02 +18 11202 -1.071110e+03 1.369000e+02 +16 11203 -2.001953e-02 4.468700e+02 +19 11203 1.338280e+03 4.299199e+02 +16 11204 -1.574200e+02 4.873500e+02 +19 11204 1.052440e+03 4.656300e+02 +16 11205 -3.236600e+02 5.020500e+02 +19 11205 7.318999e+02 5.477300e+02 +16 11206 -4.704400e+02 5.423900e+02 +19 11206 4.640100e+02 6.295701e+02 +16 11207 4.296100e+02 5.651899e+02 +18 11207 -6.365002e+01 1.152900e+02 +16 11208 -6.587700e+02 5.846700e+02 +19 11208 1.503400e+02 6.907700e+02 +16 11209 -3.449100e+02 6.112700e+02 +19 11209 6.971599e+02 7.396500e+02 +16 11210 -5.824600e+02 6.179500e+02 +19 11210 2.747600e+02 7.540100e+02 +16 11211 -3.857100e+02 6.280000e+02 +19 11211 6.218800e+02 7.736400e+02 +16 11212 -3.562900e+02 7.114000e+02 +19 11212 6.928799e+02 8.837200e+02 +16 11213 -6.892400e+02 2.245900e+02 +19 11213 7.243994e+01 8.289001e+01 +16 11214 -2.000500e+02 3.610200e+02 +19 11214 9.755200e+02 2.449199e+02 +16 11215 -1.609600e+02 3.938500e+02 +19 11215 1.043690e+03 3.075601e+02 +16 11216 -2.293600e+02 4.193700e+02 +19 11216 9.287100e+02 3.390701e+02 +16 11217 8.010010e+00 4.256799e+02 +18 11217 -9.860300e+02 1.376899e+02 +16 11218 -2.475500e+02 4.386600e+02 +19 11218 8.999800e+02 3.673000e+02 +16 11219 -1.224600e+02 4.580300e+02 +19 11219 1.112180e+03 4.245801e+02 +16 11220 -1.632800e+02 4.803900e+02 +19 11220 1.041330e+03 4.531500e+02 +16 11221 -3.726100e+02 5.253900e+02 +19 11221 6.413999e+02 5.960601e+02 +16 11222 -3.487300e+02 6.145000e+02 +19 11222 6.903501e+02 7.450500e+02 +16 11223 -4.881700e+02 6.318400e+02 +19 11223 4.379800e+02 7.808201e+02 +16 11224 -4.168000e+02 3.253000e+02 +19 11224 5.479700e+02 2.484600e+02 +16 11225 4.479980e+00 3.797600e+02 +20 11225 -8.553700e+02 -1.262800e+02 +16 11226 -3.297000e+02 3.795900e+02 +19 11226 7.165701e+02 3.338000e+02 +16 11227 -2.327800e+02 4.225300e+02 +19 11227 9.233999e+02 3.425200e+02 +16 11228 -2.327800e+02 4.225300e+02 +19 11228 9.233999e+02 3.425200e+02 +16 11229 -3.218500e+02 4.385400e+02 +19 11229 7.337300e+02 4.354099e+02 +16 11230 -1.908100e+02 4.531000e+02 +19 11230 9.960000e+02 4.033700e+02 +16 11231 -1.815000e+02 4.759600e+02 +19 11231 1.010620e+03 4.400500e+02 +16 11232 -4.466200e+02 4.812200e+02 +19 11232 5.029200e+02 5.219900e+02 +16 11233 -3.353500e+02 5.001200e+02 +19 11233 7.107400e+02 5.450200e+02 +16 11234 2.350000e+01 5.095100e+02 +19 11234 1.383260e+03 5.359099e+02 +16 11235 -2.815000e+02 5.365601e+02 +19 11235 8.174399e+02 5.944399e+02 +16 11236 -2.834000e+02 5.462800e+02 +19 11236 8.138201e+02 6.099900e+02 +16 11237 -2.200000e+01 5.544100e+02 +19 11237 1.298330e+03 6.019200e+02 +16 11238 -3.819700e+02 5.910000e+02 +19 11238 6.256899e+02 7.093500e+02 +16 11239 -4.375500e+02 6.147200e+02 +19 11239 5.253400e+02 7.542600e+02 +16 11240 -5.255500e+02 6.823400e+02 +19 11240 3.765900e+02 8.662600e+02 +17 11241 1.168080e+03 2.992900e+02 +20 11241 5.513301e+02 -2.459700e+02 +17 11242 1.168080e+03 2.992900e+02 +20 11242 5.513301e+02 -2.459700e+02 +17 11243 9.572400e+02 6.753201e+02 +18 11243 5.734800e+02 5.690991e+01 +17 11244 8.809600e+02 4.986100e+02 +20 11244 4.789301e+02 -1.896700e+02 +17 11245 8.836201e+02 7.109200e+02 +20 11245 4.798400e+02 -1.304700e+02 +17 11246 9.306201e+02 4.824399e+02 +18 11246 5.658401e+02 -4.300537e-01 +17 11247 8.361499e+02 6.724800e+02 +18 11247 5.432800e+02 5.795996e+01 +20 11247 4.709000e+02 -1.425699e+02 +17 11248 -7.545400e+02 3.638301e+02 +18 11248 9.350000e+01 -2.244995e+01 +17 11249 8.758899e+02 3.701699e+02 +18 11249 5.512100e+02 -3.783997e+01 +20 11249 4.796500e+02 -2.241300e+02 +17 11250 8.477800e+02 3.880300e+02 +18 11250 5.448301e+02 -3.175000e+01 +17 11251 1.346920e+03 3.982600e+02 +20 11251 5.992200e+02 -2.191899e+02 +17 11252 1.339390e+03 4.546599e+02 +20 11252 5.965000e+02 -2.041500e+02 +17 11253 1.188580e+03 7.797400e+02 +20 11253 5.541499e+02 -1.137800e+02 +17 11254 -1.005110e+03 8.935400e+02 +20 11254 6.880005e+01 -5.435999e+01 +17 11255 8.870701e+02 1.426600e+02 +20 11255 4.830699e+02 -2.881700e+02 +17 11256 -6.623900e+02 2.683101e+02 +20 11256 1.126300e+02 -2.399399e+02 +17 11257 1.024320e+03 3.753900e+02 +18 11257 5.928301e+02 -3.838000e+01 +17 11258 8.673501e+02 5.223700e+02 +20 11258 4.770900e+02 -1.811200e+02 +17 11259 1.208120e+03 6.243800e+02 +20 11259 5.590701e+02 -1.562200e+02 +17 11260 8.683799e+02 7.299100e+02 +18 11260 5.513999e+02 7.833008e+01 +17 11261 8.683799e+02 7.299100e+02 +18 11261 5.513999e+02 7.833008e+01 +17 11262 1.207290e+03 5.426001e+01 +18 11262 6.466799e+02 -1.450400e+02 +20 11262 5.623101e+02 -3.149000e+02 +17 11263 1.138920e+03 1.521799e+02 +18 11263 6.249399e+02 -1.131300e+02 +17 11264 -7.582800e+02 4.821899e+02 +18 11264 9.245996e+01 1.558997e+01 +17 11265 -8.104200e+02 4.829600e+02 +18 11265 7.479004e+01 1.540002e+01 +17 11266 -5.019200e+02 5.354199e+02 +18 11266 2.267000e+02 3.506006e+01 +17 11267 1.152850e+03 5.502100e+02 +18 11267 6.292200e+02 1.666003e+01 +17 11268 1.227960e+03 5.654199e+02 +18 11268 6.533899e+02 2.180005e+01 +17 11269 9.704199e+02 5.836500e+02 +18 11269 5.762900e+02 2.987000e+01 +17 11270 1.055390e+03 6.352900e+02 +18 11270 5.536799e+02 4.405005e+01 +20 11270 4.797100e+02 -1.537900e+02 +17 11271 8.713101e+02 7.483900e+02 +18 11271 5.522900e+02 8.435999e+01 +17 11272 1.156760e+03 9.111499e+02 +18 11272 6.329399e+02 1.349199e+02 +20 11272 5.451699e+02 -7.638000e+01 +17 11273 1.156760e+03 9.111499e+02 +18 11273 6.329399e+02 1.349199e+02 +20 11273 5.451699e+02 -7.638000e+01 +17 11274 9.655701e+02 9.803701e+02 +18 11274 5.826001e+02 1.585100e+02 +17 11275 1.075140e+03 9.855901e+02 +18 11275 6.136001e+02 1.595400e+02 +17 11276 9.488899e+02 1.335999e+01 +18 11276 5.691001e+02 -1.558500e+02 +17 11277 1.235770e+03 2.558997e+01 +18 11277 6.546399e+02 -1.548600e+02 +20 11277 5.700100e+02 -3.236500e+02 +17 11278 -6.816100e+02 1.053101e+02 +18 11278 1.173101e+02 -1.060601e+02 +17 11279 -7.110601e+02 1.043000e+02 +18 11279 1.065500e+02 -1.057600e+02 +17 11280 1.393970e+03 1.430500e+02 +18 11280 7.062800e+02 -1.171000e+02 +17 11281 1.357620e+03 1.882400e+02 +18 11281 6.949600e+02 -1.016400e+02 +17 11282 1.083630e+03 2.083700e+02 +18 11282 6.099399e+02 -9.362000e+01 +20 11282 5.302100e+02 -2.714100e+02 +17 11283 1.012840e+03 2.314900e+02 +18 11283 5.897500e+02 -8.485999e+01 +20 11283 5.129301e+02 -2.637900e+02 +17 11284 9.783201e+02 5.045500e+02 +18 11284 5.788201e+02 4.920044e+00 +17 11285 1.219840e+03 1.430005e+01 +18 11285 6.508401e+02 -1.579301e+02 +17 11286 -5.877700e+02 1.075400e+02 +18 11286 1.458199e+02 -1.054900e+02 +20 11286 1.323000e+02 -2.852900e+02 +17 11287 1.368530e+03 1.535801e+02 +20 11287 6.059900e+02 -2.877400e+02 +17 11288 1.183100e+03 1.752200e+02 +18 11288 6.391899e+02 -1.050601e+02 +17 11289 3.133401e+02 2.313700e+02 +18 11289 5.190500e+02 -5.742004e+01 +20 11289 4.503199e+02 -2.405200e+02 +17 11290 -8.726100e+02 3.310100e+02 +20 11290 5.554004e+01 -2.232000e+02 +17 11291 1.351820e+03 3.992300e+02 +18 11291 6.927400e+02 -3.343005e+01 +17 11292 1.071760e+03 4.733900e+02 +20 11292 5.256700e+02 -1.970000e+02 +17 11293 -8.163900e+02 4.969900e+02 +20 11293 7.005005e+01 -1.779301e+02 +17 11294 -8.163900e+02 4.969900e+02 +18 11294 7.441003e+01 1.971997e+01 +20 11294 7.005005e+01 -1.779301e+02 +17 11295 1.287350e+03 5.855500e+02 +18 11295 6.717900e+02 2.727002e+01 +17 11296 1.017330e+03 6.256599e+02 +18 11296 5.889500e+02 4.218994e+01 +17 11297 1.071460e+03 6.513401e+02 +18 11297 6.050500e+02 5.087000e+01 +17 11298 8.773000e+02 7.787000e+02 +18 11298 5.507500e+02 9.387000e+01 +17 11299 1.009970e+03 7.909500e+02 +18 11299 5.877400e+02 9.602002e+01 +17 11300 5.721001e+02 8.944600e+02 +18 11300 7.159800e+02 1.980000e+02 +20 11300 6.113000e+02 -2.081000e+01 +17 11301 5.530901e+02 8.946299e+02 +20 11301 6.053999e+02 -2.087000e+01 +17 11302 3.276101e+02 2.316899e+02 +18 11302 5.242600e+02 -5.753003e+01 +20 11302 4.544700e+02 -2.405100e+02 +17 11303 1.394820e+03 2.692400e+02 +18 11303 7.064199e+02 -7.612000e+01 +20 11303 6.123799e+02 -2.555200e+02 +17 11304 1.377650e+03 2.927400e+02 +18 11304 7.014600e+02 -6.812000e+01 +17 11305 1.104140e+03 4.069099e+02 +20 11305 5.344500e+02 -2.162000e+02 +17 11306 1.359830e+03 5.798800e+02 +18 11306 6.947100e+02 2.571997e+01 +20 11306 6.001201e+02 -1.682800e+02 +17 11307 1.130070e+03 5.989299e+02 +18 11307 6.222600e+02 3.246997e+01 +17 11308 1.188720e+03 6.003800e+02 +18 11308 6.404199e+02 3.273999e+01 +17 11309 1.172850e+03 6.122800e+02 +18 11309 6.353601e+02 3.683997e+01 +17 11310 -9.188900e+02 9.508701e+02 +18 11310 1.236700e+02 1.823401e+02 +17 11311 1.048120e+03 2.207500e+02 +18 11311 6.001699e+02 -8.871997e+01 +17 11312 3.032800e+02 5.222100e+02 +18 11312 5.171200e+02 4.398999e+01 +17 11313 -1.170190e+03 1.002900e+03 +18 11313 2.350000e+01 1.969700e+02 +19 11314 1.043200e+03 2.637300e+02 +20 11314 -1.088210e+03 -1.195500e+02 +-3.4265630475549310e-03 +9.6448984178004217e-03 +4.6562227695769124e-03 +8.2039923232261648e-03 +4.1758870714924805e-04 +1.0139126763172436e-01 +2.8443148232166736e+03 +-2.0200951857532239e-08 +2.1246398231307891e-15 +-7.6437505710887255e-02 +5.1618114951068872e-01 +-1.7442810285789871e-02 +4.6893128037549031e-01 +1.0998232772145669e-01 +9.0492419026091042e-01 +3.9540291001121768e+03 +9.6418592733938310e-11 +-1.5808016021067602e-15 +1.9067231923145704e-03 +6.0710949498447830e-01 +7.8489923141725915e-03 +8.8038276503254886e-01 +-1.0646277417857433e-01 +-1.1935373802183664e+00 +4.7887838483304304e+03 +-2.1102288146435240e-08 +2.0588270479666084e-14 +-6.2533665385189063e-02 +6.1941847444116560e-01 +-9.5483305526211752e-03 +7.7003287828216804e-01 +1.1651582581324335e-01 +9.8661798833669079e-01 +3.8008881743835727e+03 +-2.8145802517533521e-09 +3.5846594123306624e-16 +1.2386901636826481e-01 +-1.9482716735636227e-01 +1.3764127718237226e-02 +4.2879230810800784e-01 +1.6016832076091836e-02 +-1.0778520056930145e+00 +2.2016139922502152e+03 +-1.6152550522785315e-08 +8.7137446318732256e-16 +1.9122007152921933e-01 +-4.4427586802559156e-02 +1.6507611107040324e-01 +-9.8170429495478412e-03 +9.4489030398391793e-02 +-6.9740483496458483e-01 +2.6562450346611104e+03 +-1.5770005494039636e-08 +1.5405076330938909e-15 +-9.1711782794874519e-02 +3.5723374938806746e-01 +-5.3488345815837904e-02 +1.1145554481603703e-01 +1.5380223634177648e-01 +1.0818540636187013e+00 +2.5886235256764344e+03 +2.3391481076237295e-09 +-5.0767394723894051e-15 +9.6082401704867718e-02 +3.0773645407239508e-01 +2.5147054565130902e-02 +6.3295339595872280e-01 +3.0686196527989623e-03 +-1.2675623030016712e+00 +3.0193521448475844e+03 +-4.2306540861986955e-09 +-2.0499307348978108e-16 +-2.4128963839393391e-02 +3.0029926990149458e-01 +1.0862208728002057e-03 +-1.1394725719141723e-01 +2.5751765293598475e-02 +3.9281273652038085e-01 +4.1674816947028448e+03 +-7.9462988718401827e-09 +-3.8426370922257509e-16 +6.1035291489566539e-02 +5.7733726740212798e-01 +3.2968977758267862e-02 +7.0286731467539754e-01 +-1.1725853932612409e-01 +-2.1278001513363005e+00 +4.5729719222846952e+03 +-1.2387039104975495e-09 +-1.1177432297793695e-16 +-1.5646588771550574e-01 +5.5847471923803538e-01 +-2.7714922597332704e-02 +6.3234965517408925e-01 +-3.1758229037698171e-01 +-1.2658770106009034e+00 +2.6837290876884258e+03 +-2.1004246945168424e-08 +1.2750378585220006e-15 +4.5840820689215300e-02 +4.5320417376062172e-01 +3.0171238581507859e-02 +1.0557651771669538e+00 +-1.4076275321937481e-01 +-1.9800792906704539e+00 +4.3436514940166026e+03 +1.9070799519562368e-08 +2.5891561792423129e-15 +-1.1988164815915682e-01 +6.8853987270183581e-01 +-4.4206723625395579e-02 +1.8322953581404944e-01 +-5.2356329762854659e-01 +-2.0282799981950403e+00 +3.4743131408884051e+03 +-9.4176269962886827e-09 +4.2804930614898483e-16 +2.0246566902893736e-02 +6.1973863395790607e-01 +-3.9396185755239781e-03 +5.7450263723865858e-01 +-7.2720598146057719e-02 +-1.3445193819845049e+00 +1.2324809007098627e+04 +-1.3793461623821485e-09 +4.8392431937984706e-19 +1.0707079958577236e-01 +4.0595424502654215e-02 +-7.0739691496062053e-03 +8.5087246545982487e-01 +1.2078592731411888e-03 +-1.2497770605378461e-01 +1.3622159951134606e+03 +-7.7233942262293523e-08 +2.9442364629639154e-14 +5.2248266538963438e-02 +-4.3096281619092192e-01 +1.2825028268385991e-02 +8.7861633187912380e-01 +-8.0586403545652593e-02 +-5.4145439168621301e-01 +2.2475126892697440e+03 +-3.2135886415355696e-08 +2.8103450196256805e-15 +1.3061109543886920e-01 +1.1520775368937985e-01 +4.6564012809048191e-02 +5.2285137059451192e-01 +3.5221935575352400e-02 +-9.8715767975082980e-01 +2.1932172309128428e+03 +-2.8016206771425212e-08 +7.4260302767109987e-15 +5.1048252446509811e-02 +9.4081374969406040e-01 +1.8816416391403416e-02 +6.1091127020155422e-01 +-5.3593834934716103e-02 +-1.3456186591763710e+00 +6.9180940454902848e+03 +7.2551752356271652e-09 +2.2480596705562579e-17 +2.5688747550683767e-02 +6.6163299320464486e-01 +-1.8946496681373811e-03 +4.6168322818420049e-01 +-2.2131497240140569e-01 +-2.0689014971838970e+00 +2.7833252041164828e+03 +-2.0910954720246339e-08 +3.9178887966566628e-15 +4.3304795999366975e-03 +-3.0024888322581328e-01 +2.6825207310567985e-02 +5.7037124545449136e-01 +2.8752218728373316e-02 +4.8592331500942221e-02 +2.9774748039273991e+03 +2.6089048471444772e-09 +-2.6374190644059743e-15 +-5.5282628230888045e-02 +6.6233954470511636e-01 +-2.2231499219427752e-02 +4.7721056206261558e-01 +-3.8717431709821393e-01 +-2.0420387340792576e+00 +2.3818056873313799e+03 +-1.3362493005972273e-08 +1.7483249922136956e-15 +1.7926522973269743e+00 +5.2748012453575732e-01 +-3.1026912014672661e+00 +1.8303432669336086e+00 +5.3027611196776936e-01 +-3.0808147495680887e+00 +5.8722331627710345e-01 +2.2972675882726537e-01 +-2.7496653629260410e+00 +1.3299657078031248e+00 +2.4369264376721886e-01 +-2.4053230729389754e+00 +1.8659577433042436e+00 +5.2698132538294495e-01 +-3.0603282803622025e+00 +1.8453427938484068e+00 +5.3267274620790062e-01 +-3.0632545228995318e+00 +5.1296921748093816e-01 +3.7835741686102725e-01 +-2.6791557035967726e+00 +1.8486343424636604e+00 +5.1680554448290328e-01 +-3.0698785461663709e+00 +1.8249967372580809e+00 +5.4442856649833682e-01 +-3.0996522669029174e+00 +4.2815345549210071e-01 +4.0403932244139995e-01 +-2.6552785271757200e+00 +1.3886026567288254e+00 +1.5034998608368652e-01 +-2.2922145512054413e+00 +1.3888562254542423e+00 +1.5032258799020801e-01 +-2.2923944476840288e+00 +5.2029533847568987e-01 +1.6651496445533265e-01 +-2.6875624787111065e+00 +1.3375814138436444e+00 +1.4927394129154575e-01 +-2.3543077709179103e+00 +1.3876463506061265e+00 +2.3283405926743378e-01 +-2.6017323181450038e+00 +1.7896417462404333e+00 +5.4326460309396285e-01 +-3.1046215551284773e+00 +1.7885652939990557e+00 +5.4297553629370565e-01 +-3.1040888788979726e+00 +4.4250466432426788e-01 +4.2502274856835087e-01 +-2.6677951007187644e+00 +1.8281074612663457e+00 +4.8882489547718233e-01 +-4.5937482975703041e+00 +1.8236564504097161e+00 +4.8707688886999062e-01 +-4.5826294922125772e+00 +1.8082100915057351e+00 +2.7922382080618657e-01 +-4.4602458189272181e+00 +1.8504716336639075e+00 +2.4033290203545168e-01 +-4.4377194508791042e+00 +1.8209107702464751e+00 +2.7270816496626765e-01 +-4.4587542852471636e+00 +1.8209377072145911e+00 +5.0145431127017503e-01 +-4.5769931494634744e+00 +1.8351216534679879e+00 +5.4138857808069574e-01 +-3.0735154752084592e+00 +9.4249879679731174e-01 +1.7821581122662558e-01 +-3.1106244989994436e+00 +8.8706540474228746e-01 +1.9640903165191267e-01 +-3.0529282434467726e+00 +8.2636835777720208e-01 +1.6852736636278121e-02 +-2.9754388780892498e+00 +8.5166719326981122e-01 +2.6871007187847493e-02 +-3.0073793596915501e+00 +8.6527914493380398e-01 +1.3316440626912357e-01 +-3.0061931359554253e+00 +9.9009918333943159e-01 +1.8576996242703592e-01 +-3.1763896043808115e+00 +7.0309211838351615e-01 +2.3598280681428277e-01 +-2.8568157008062065e+00 +7.0309211838351615e-01 +2.3598280681428277e-01 +-2.8568157008062065e+00 +9.1341908383129444e-01 +1.1826581969073875e-01 +-3.0894320192484339e+00 +8.0223602740829369e-01 +1.2650308445291547e-01 +-2.9444402167993053e+00 +1.0210176140748020e+00 +1.2578630837393151e-01 +-3.1996911681994162e+00 +9.8097317408799956e-01 +1.2810446308520809e-01 +-3.1625507987861177e+00 +1.0120417443881917e+00 +2.4830795244853721e-01 +-3.2142911046050036e+00 +6.5497275161888491e-01 +2.3761365110569060e-01 +-2.8035225628389240e+00 +1.2201218837705026e+00 +2.7319900385605550e-01 +-3.4907441264614234e+00 +7.7681579001246803e-01 +2.6317469817137074e-01 +-2.9264824034807253e+00 +1.8459683100706403e+00 +3.2555214349628819e-01 +-4.4472604454952522e+00 +6.2790938050196621e-01 +7.4426344068077785e-02 +-2.7737205200348249e+00 +1.0078304287882707e+00 +1.4000821533178404e-01 +-3.2026272604981929e+00 +1.0322951592563310e+00 +1.8210502545437485e-01 +-3.2202118828901445e+00 +9.0980770209388351e-01 +1.8965609675454137e-01 +-3.0810063983454583e+00 +9.1793088566325820e-01 +2.1428781289766188e-01 +-3.0872364584341412e+00 +6.4953546414370666e-01 +2.6726288003869775e-01 +-2.7970935182229386e+00 +6.0552735326769713e-01 +1.6181274295402776e-01 +-2.7628051153629110e+00 +1.0173167629858118e+00 +1.8493671974579098e-01 +-3.2145133351529327e+00 +1.3885895298899773e+00 +2.6773382650846123e-01 +-2.2925424941371393e+00 +7.8100164167378872e-01 +9.3385794963070173e-02 +-2.9246269116596446e+00 +1.0276842806042121e+00 +2.0992684931811265e-01 +-3.2203193866114486e+00 +7.9042019190953694e-01 +2.2693769650612539e-01 +-2.9361296117852964e+00 +1.8230269899676788e+00 +5.0223345986795309e-01 +-4.5821073053470203e+00 +1.3330213389075412e+00 +1.6860082210438487e-01 +-2.3632264454621641e+00 +1.7826675033924135e+00 +5.3447729155392465e-01 +-3.1073696956678822e+00 +1.7926522973269743e+00 +5.2748012453575732e-01 +-3.1026912014672661e+00 +5.8886065337220317e-01 +3.5059575927272524e-01 +-2.7453999547151922e+00 +4.2942249988978026e-01 +4.1882644703664423e-01 +-2.6573173028182282e+00 +1.3311044887010184e+00 +1.9652897694347995e-01 +-2.3609078077029837e+00 +1.2997947421970353e+00 +3.6723476114681936e-01 +-3.6894052649861182e+00 +8.4582403805597361e-01 +4.1775268066985005e-01 +-3.1707750344713124e+00 +4.2938595896262055e-01 +4.1880557563149790e-01 +-2.6573057481037194e+00 +1.0246021747366632e+00 +9.9757102488915630e-02 +-3.2120200977237419e+00 +1.0172821222010364e+00 +1.0831313287998791e-01 +-3.2085374933031106e+00 +1.0522674496014774e+00 +1.1225403561797657e-01 +-3.2428810852835159e+00 +8.2674884041751129e-01 +9.7978051178304354e-02 +-2.9744254270352521e+00 +1.8503097729817657e+00 +2.6779499074340324e-01 +-4.4190553724010062e+00 +8.7026872646383713e-01 +2.8119431192837864e-02 +-3.0297553644791115e+00 +1.0525719173501209e+00 +8.5436353360789877e-02 +-3.2451689716969341e+00 +1.0617719744815235e+00 +8.8555013681385783e-02 +-3.2564940701612226e+00 +5.1095330072924072e-01 +2.7864606607987924e-01 +-2.6645141302633100e+00 +5.8033518060817291e-01 +8.1280563399433500e-02 +-2.7385682894858987e+00 +1.3320437160717602e+00 +2.4468273510979854e-01 +-2.3817303306978435e+00 +5.0674941866082357e-01 +3.1420381145764414e-01 +-2.6877813945067528e+00 +5.2943874334717134e-01 +3.3774148255610303e-01 +-2.6954386578260805e+00 +5.0775041636027474e-01 +3.4647836062820919e-01 +-2.6922636839476866e+00 +4.5920431662566386e-01 +3.7045117714738796e-01 +-2.6521184096054138e+00 +5.4318275941996153e-01 +7.9040231772960573e-02 +-2.6935275792575810e+00 +6.3864250627644492e-01 +8.6569282379231741e-02 +-2.7752223385147499e+00 +1.3322315085183625e+00 +1.6851151491833899e-01 +-2.3624384954663902e+00 +7.7821349966885756e-01 +2.3342645005547447e-01 +-2.9376410331209200e+00 +6.8169590371883093e-01 +2.5074704316137136e-01 +-2.8230123582942630e+00 +6.4580231119550036e-01 +2.5291937427959621e-01 +-2.7988417454593182e+00 +1.3261799125391276e+00 +9.1439904265058630e-02 +-2.3741563711368725e+00 +1.3316643062654858e+00 +1.5348079915526294e-01 +-2.3701624770360663e+00 +5.4341502073670034e-01 +1.6461364612911317e-01 +-2.6996196314515046e+00 +7.7101406688301155e-01 +2.1913465813642183e-01 +-2.9227574488133667e+00 +6.8288032477704386e-01 +2.2460006608984587e-01 +-2.8425524910966296e+00 +4.6952318706928564e-01 +2.4572834488324646e-01 +-2.6659307583174394e+00 +1.3227701834044354e+00 +2.5556457053802267e-01 +-2.4074639125357895e+00 +4.4066443398977295e-01 +4.1238145161539019e-01 +-2.6573200447303198e+00 +1.3260820667085580e+00 +8.4554900313813450e-02 +-2.3971312873293615e+00 +1.3207357812887333e+00 +1.6889857552406301e-01 +-2.4411801204911572e+00 +9.1807989278071356e-01 +1.8116376830218486e-01 +-3.0855648279622683e+00 +5.1096493977061197e-01 +1.7404865307018977e-01 +-2.6845223962704221e+00 +7.6395185060111814e-01 +2.1361030609035017e-01 +-2.9331292902193531e+00 +1.3862947832317363e+00 +2.4924053012611488e-01 +-2.5925279826164780e+00 +4.3115158795950220e-01 +3.5496031831246655e-01 +-2.6642441850599252e+00 +4.2945180787287912e-01 +3.8501257710866083e-01 +-2.6495161504294176e+00 +4.8716434216696769e-01 +4.0321931538504013e-01 +-2.6764215008932295e+00 +6.1680975324831777e-01 +9.7499407886784281e-02 +-2.7684227083756539e+00 +5.3310309126689048e-01 +1.0122154412542834e-01 +-2.6934905678610241e+00 +7.7491785697709714e-01 +1.2210411584919392e-01 +-2.9298512181413212e+00 +1.4920066585802616e+00 +1.6845191649176702e-01 +-2.6303838718999017e+00 +1.4920066585802616e+00 +1.6845191649176702e-01 +-2.6303838718999017e+00 +5.5101556878602154e-01 +1.5537832089105263e-01 +-2.7080646192722519e+00 +1.3231535365574014e+00 +1.5374376742374574e-01 +-2.4227508296937348e+00 +5.1614761684695043e-01 +1.5765194143362279e-01 +-2.6841126171069312e+00 +1.3328392864038767e+00 +2.0145972344027477e-01 +-2.3551325095494731e+00 +5.2472898445755767e-01 +2.4334214132048701e-01 +-2.6949250307282075e+00 +1.3415658049021417e+00 +2.5104071658349814e-01 +-2.3513584695520482e+00 +1.3237192707786478e+00 +2.5872783318840559e-01 +-2.4456002525898439e+00 +1.3283191245393018e+00 +2.5922735002024921e-01 +-2.3888220636439046e+00 +1.3364137864118377e+00 +2.6080581495492522e-01 +-2.3703700633223819e+00 +1.3339208730779446e+00 +2.6037704302254189e-01 +-2.3583460832540046e+00 +4.5183208154082977e-01 +4.2193821366789830e-01 +-2.6660562189700512e+00 +4.7818304426562669e-01 +4.4325410775845392e-01 +-2.6789470812117182e+00 +5.4251955011901043e-01 +1.0804307509553389e-01 +-2.6969974235139320e+00 +1.3231209234475976e+00 +1.4748281903545751e-01 +-2.4343079849161144e+00 +1.3303135350387174e+00 +1.4922324226562664e-01 +-2.3701499279793294e+00 +6.7452250653145174e-01 +1.9907160261785795e-01 +-2.8391176962844136e+00 +7.8255438292374135e-01 +2.2663125084659982e-01 +-2.9336804109200125e+00 +1.3251687311303690e+00 +2.4918117999520195e-01 +-2.4306883000204600e+00 +1.3830577581034726e+00 +2.5704510803840686e-01 +-2.6000285727400403e+00 +1.3238302055642115e+00 +2.5371351232501993e-01 +-2.4360642899612972e+00 +1.3263521851078055e+00 +2.5864599901667035e-01 +-2.4315011607094879e+00 +1.3233668853830654e+00 +2.6486056736491798e-01 +-2.4346911899566450e+00 +1.3288316621931651e+00 +2.6589710882805428e-01 +-2.3718577912672107e+00 +4.4953437984980921e-01 +2.6455580378398535e-01 +-2.6581837859491264e+00 +4.9158080358306427e-01 +2.6897675839188684e-01 +-2.6729877506578088e+00 +4.6911243982172685e-01 +2.6875413014018829e-01 +-2.6651302843900981e+00 +4.7675180157453723e-01 +2.7078953166283659e-01 +-2.6676668005793744e+00 +5.4514220692200566e-01 +3.4019769906862640e-01 +-2.7075553963852457e+00 +4.2213536142832936e-01 +3.6183896745620836e-01 +-2.6579260284783794e+00 +5.7686351021829574e-01 +3.7938492036167309e-01 +-2.7278574679850651e+00 +4.1433223221440135e-01 +3.8485000186198393e-01 +-2.6488398550752250e+00 +4.1995837184920809e-01 +4.5525690457734147e-01 +-2.6565701657145748e+00 +8.2953513287953640e-01 +7.1228438692996610e-02 +-2.9811700318185292e+00 +8.0018432244892901e-01 +7.7242743491370183e-02 +-2.9442172394512700e+00 +8.0944638194911056e-01 +1.0903421499034202e-01 +-2.9540107959412136e+00 +8.0044982313105251e-01 +1.1425139871026684e-01 +-2.9436398951122502e+00 +5.8865506388024946e-01 +1.4981515023666117e-01 +-2.7442947163325515e+00 +1.3200823580646928e+00 +1.5532303448444104e-01 +-2.4291896803965010e+00 +4.7049391523467909e-01 +1.6609925181553545e-01 +-2.6665748804001392e+00 +6.8283370921383046e-01 +2.0274946579856171e-01 +-2.8434535633615918e+00 +7.8226815124249938e-01 +2.3590409779330326e-01 +-2.9332080948642276e+00 +6.4517371662514711e-01 +2.3909800972100886e-01 +-2.8026478552067693e+00 +5.8570992928839738e-01 +2.5258648426609387e-01 +-2.7423881738003337e+00 +1.3394006486879158e+00 +2.5577618392578655e-01 +-2.3566229815942976e+00 +8.0334805444835145e-01 +2.7094724573525936e-01 +-2.9440017800264338e+00 +5.2616176543261506e-01 +2.6736885583861753e-01 +-2.6900265759637638e+00 +5.1269309962863585e-01 +2.6732386571264338e-01 +-2.6825925261491070e+00 +4.8315251325660197e-01 +2.6719081150166418e-01 +-2.6691046829337619e+00 +5.0578785075537702e-01 +2.6983100285626599e-01 +-2.6781024510998175e+00 +4.4784722177354708e-01 +2.9062361787027835e-01 +-2.6422060807033332e+00 +4.3894514076915470e-01 +3.5674418971395327e-01 +-2.6591514438058894e+00 +1.3422159568924008e+00 +7.2347046070157225e-02 +-2.3434102411788147e+00 +8.0967881947428388e-01 +1.0907801506456206e-01 +-2.9546922775403739e+00 +1.3852235316995862e+00 +1.0730207589776407e-01 +-2.5974651119223773e+00 +5.8152574819737257e-01 +1.3856339008227286e-01 +-2.7411890384850413e+00 +5.4870382449737898e-01 +1.5831119553732945e-01 +-2.7046683519554922e+00 +1.3333648798790845e+00 +1.6083257176213175e-01 +-2.3539428174989254e+00 +5.6599768807093032e-01 +1.7544197479030219e-01 +-2.7231398697096436e+00 +5.6045506829704184e-01 +2.1853062913051730e-01 +-2.7215690525194773e+00 +8.0167730704596629e-01 +2.6132044063259008e-01 +-2.9468059354368199e+00 +4.4376151449581747e-01 +2.5656923911069296e-01 +-2.6546000491118855e+00 +5.1874518601029773e-01 +2.6762586106140807e-01 +-2.6846685960107708e+00 +1.3355321252871626e+00 +2.8008330289189626e-01 +-2.3569234808869535e+00 +1.8283757206498685e+00 +5.1431973924443208e-01 +-4.5957629843144865e+00 +4.3449212199605003e-01 +3.7910045082629218e-01 +-2.6496982234007227e+00 +1.7781589869503545e+00 +4.8113416340750320e-01 +-3.1036439700569249e+00 +1.7786866097351759e+00 +4.8151630749068286e-01 +-3.1044715893437274e+00 +1.8403304554897473e+00 +4.9894804110796687e-01 +-3.0620744941661813e+00 +4.8904430508094809e-01 +4.4797121017552849e-01 +-2.6740490213508612e+00 +7.8797216578135998e-01 +6.5534574310155413e-02 +-2.9312433611317181e+00 +7.8080021866767169e-01 +7.3573678169329887e-02 +-2.9262108340238133e+00 +1.3239046835206305e+00 +7.0530939455036926e-02 +-2.3825960517670901e+00 +7.8971336142527171e-01 +1.1621827563700379e-01 +-2.9344401632194086e+00 +8.0074587814876486e-01 +2.4581597196918911e-01 +-2.9436695381301177e+00 +1.3852359508510266e+00 +2.4285180560957800e-01 +-2.6001441175278810e+00 +4.2132574711907139e-01 +3.7594459488623505e-01 +-2.6504900032347800e+00 +4.7648938527475609e-01 +3.9666070683001953e-01 +-2.6721566225182150e+00 +1.3267682244975434e+00 +9.2515677089441528e-02 +-2.3692608086920561e+00 +5.4132711940187339e-01 +2.5665158043787906e-01 +-2.7022569040567448e+00 +1.3706059937707018e+00 +2.0981624643948005e-01 +-2.3158576198372636e+00 +1.3805333314922226e+00 +1.7014120319791098e-01 +-2.2972097092913817e+00 +7.2424902984869821e-01 +2.4791690720216797e-01 +-2.8623237233717220e+00 +7.5304833916243918e-01 +1.2039551767639747e-01 +-2.9081406540713646e+00 +6.6035501810813890e-01 +1.6668037713673137e-01 +-2.8125545326526713e+00 +6.4820267638178675e-01 +2.2449126246166354e-01 +-2.8050311956302267e+00 +5.9422496467377117e-01 +1.7967067522829833e-01 +-2.7487681010174150e+00 +6.3584821828709748e-01 +1.9538986195616329e-01 +-2.7940760367925428e+00 +6.9725288772357275e-01 +2.1558099403474121e-01 +-2.8575148662796224e+00 +9.0574977820059965e-01 +2.2082442178719006e-01 +-3.0811808788084925e+00 +9.4340566592750241e-01 +1.7836007285545735e-01 +-3.1134290113052510e+00 +8.3271568090293213e-01 +7.0760192096620392e-02 +-2.9908144125887794e+00 +6.2924746419243860e-01 +2.7301343119887994e-01 +-2.7840054103015177e+00 +8.5195009056901438e-01 +1.2345538001717291e-01 +-3.0044773856027680e+00 +9.4869859826814851e-01 +1.2936238178954590e-01 +-3.1295262834030497e+00 +8.5564519951173346e-01 +1.9318379873967317e-01 +-3.0121082869906561e+00 +8.0229889323646220e-01 +9.4331836865542584e-02 +-2.9499986053406353e+00 +9.6209971256879467e-01 +1.4321765493476893e-01 +-3.1482714841095492e+00 +5.5925505027757028e-01 +1.6368036451401966e-01 +-2.7215579806402581e+00 +4.6624406555951597e-01 +4.2235153870532904e-01 +-2.6709653421384849e+00 +5.2835012416377558e-01 +3.7010050452012522e-01 +-2.6890445884681302e+00 +5.4812253136922273e-01 +2.9494733626033642e-01 +-2.6931605360225572e+00 +4.0875889017038025e-01 +4.5446920602037266e-01 +-2.6476604432741069e+00 +4.7271498704396203e-01 +4.2162521647594181e-01 +-2.6770893745590838e+00 +5.3555674664260589e-01 +4.0680713750105035e-01 +-2.7013174963910664e+00 +5.0597170419248638e-01 +4.1331132838892748e-01 +-2.6870461371156722e+00 +5.4381507518568917e-01 +3.3036143155815711e-01 +-2.7020972305559128e+00 +7.7968465925294961e-01 +6.5629995621471537e-02 +-2.9246102781013787e+00 +7.9133366043558628e-01 +1.6098953277665101e-01 +-2.9393484628017585e+00 +1.0268404716645771e+00 +2.4225422701177615e-01 +-3.2249019096410891e+00 +7.9818542486191679e-01 +5.0371157698659609e-02 +-2.9432860482967285e+00 +7.7823322915629356e-01 +2.3335830040603564e-01 +-2.9374388159007325e+00 +1.0153146254805927e+00 +1.5028208598835405e-01 +-3.2111513642719931e+00 +4.9441281630682288e-01 +3.3196798956936530e-01 +-2.6821523888104331e+00 +5.2231689660345981e-01 +1.6059367930041410e-01 +-2.6830988026459783e+00 +1.3456394957608235e+00 +9.8163483542056687e-02 +-2.3438877358907200e+00 +1.3864477471988499e+00 +1.6227404490101482e-01 +-2.2942687365518242e+00 +6.2696419049851926e-01 +8.9971811591305809e-02 +-2.7780479306922903e+00 +8.2546245983204580e-01 +1.3433756822621543e-01 +-2.9699141334014407e+00 +8.4572143730651517e-01 +4.7580734026114305e-02 +-3.0004803296413569e+00 +1.0356438813992095e+00 +9.5569148195533971e-02 +-3.2255317742134193e+00 +5.8111667473372830e-01 +2.5270684426916190e-01 +-2.7435075692479702e+00 +1.8476902755389948e+00 +3.0363274713468841e-01 +-4.4262928149214105e+00 +9.0194314400284503e-01 +1.8073008665529200e-01 +-3.0748473592285763e+00 +1.3862849732935243e+00 +2.0275703891305488e-01 +-2.2931255203605510e+00 +3.8456457315031463e+00 +4.8324197668528895e-01 +-7.9087054832656865e+00 +4.5148679075264625e-01 +3.5871511043856663e-01 +-2.6646600299829810e+00 +1.3373734838307392e+00 +1.2327258573703322e-01 +-2.3534854881057128e+00 +5.1954755684439502e-01 +2.6827014879442146e-01 +-2.6858017654307456e+00 +1.3578208588737952e+00 +2.8076211946468982e-01 +-2.3325315464180827e+00 +7.0418107431375998e-01 +2.2459474128113949e-01 +-2.8562434765486184e+00 +4.3091657924579174e-01 +3.6136154027645540e-01 +-2.6601667029617220e+00 +5.6707161217969926e-01 +2.3433303821740037e-01 +-2.7207111495847163e+00 +1.5211083358678494e+00 +2.8268696520862174e-01 +-2.6452848070074020e+00 +1.1694499121313564e+00 +1.6472562820309999e-01 +-3.4069487139476551e+00 +8.5215263963087640e-01 +1.4966058816635597e-02 +-3.0044637694427472e+00 +8.5297137456001038e-01 +5.4359703666473372e-02 +-3.0069772879761030e+00 +7.2544641754135075e-01 +1.9858302127784655e-01 +-2.8917495853538040e+00 +6.3843966116023732e-01 +2.7446473766837148e-01 +-2.7814621929792942e+00 +7.1966758918183371e-01 +2.1427074709525470e-01 +-2.8836385200308805e+00 +1.3812049880020383e+00 +1.9777762777980940e-01 +-2.2957864474054910e+00 +9.1081393837060109e-01 +3.1212122729159053e-01 +-3.0917340384501362e+00 +7.8821889214082719e-01 +5.1880265982663494e-02 +-2.9315141801044664e+00 +7.2842704033799022e-01 +6.0871336072139286e-02 +-2.8777166010769233e+00 +8.0947781250920581e-01 +1.1522901142140540e-01 +-2.9559623685841574e+00 +6.3591101963777219e-01 +1.7377338788844265e-01 +-2.7918411495593500e+00 +1.3779030096244829e+00 +2.0259761033237253e-01 +-2.3009482113750517e+00 +9.2020337851531464e-01 +3.0012607993530516e-01 +-3.0916789758195722e+00 +5.9004788278311759e-01 +7.4155410321523618e-02 +-2.7394339982465570e+00 +7.3183017873766010e-01 +1.2382471487432423e-01 +-2.8944377909812342e+00 +7.9063264248760756e-01 +9.7421889732139805e-02 +-2.9353290669407941e+00 +4.7484219532976690e-01 +4.0759190496099784e-01 +-2.6711531246591322e+00 +4.7300027743009865e-01 +1.7956491302481803e-01 +-2.6595589566864470e+00 +4.4037851549486196e-01 +4.0623767110391146e-01 +-2.6618074333368558e+00 +4.4485009475695142e-01 +3.6020375420918416e-01 +-2.6543660988530875e+00 +4.5090091730905807e-01 +4.2590192808998834e-01 +-2.6668436208644688e+00 +4.6500269030414415e-01 +3.9829805907763605e-01 +-2.6704533286751464e+00 +4.8234158303668989e-01 +4.4914624600655284e-01 +-2.6738227324329125e+00 +4.7254141790684739e-01 +4.0036847219129057e-01 +-2.6750127178559246e+00 +6.0428095829841477e-01 +2.2124824707466828e-01 +-2.7544652460368937e+00 +6.7802382650119419e-01 +2.3766581227634462e-01 +-2.8275594525876890e+00 +7.0859419560921122e-01 +2.1147113485600610e-01 +-2.8756851919213777e+00 +5.4688444182216822e-01 +2.6516897096342013e-01 +-2.7016580334697324e+00 +7.2523736730415478e-01 +1.8189173148188162e-01 +-2.8860226370773776e+00 +5.4162504613130258e-01 +2.6018813035802157e-01 +-2.6999750038370065e+00 +5.3850331997496215e-01 +2.6606976553611095e-01 +-2.6967965890637298e+00 +5.3666070750363415e-01 +3.6840981113246551e-01 +-2.6972749130108662e+00 +4.4202128132739005e-01 +3.7211647663341807e-01 +-2.6545715404517138e+00 +4.9641316545017788e-01 +6.8644733697750676e-02 +-2.6571049388036472e+00 +5.3565556896706401e-01 +2.3284611467422309e-01 +-2.6985451491639658e+00 +1.1892870764593371e+00 +2.0981312915294495e-01 +-3.4401530246046161e+00 +1.8437249801128646e+00 +4.3619647107680509e-01 +-4.5683291611874850e+00 +1.3724218442741165e+00 +2.4742967384259645e-01 +-2.3170533402969942e+00 +1.3709970343643609e+00 +1.8189526979170290e-01 +-2.3059672069337851e+00 +6.4799788545084369e-01 +2.5345357000120311e-01 +-2.7954943079926289e+00 +1.3629325035954318e+00 +7.2383086133715219e-02 +-2.3047333198127657e+00 +8.2412634119338946e-01 +-2.7140777432962115e-02 +-2.9691523156210060e+00 +7.9540312721321882e-01 +-2.8035648775738251e-02 +-2.9381171505804460e+00 +8.4381208533759489e-01 +4.7042940853512946e-02 +-2.9951431661116477e+00 +1.3702923546991033e+00 +2.8118502093426362e-01 +-2.3172354484752002e+00 +8.9621861776358014e-01 +1.8753461849275979e-01 +-3.0717792011709535e+00 +3.8761063513972664e+00 +4.7771223991189227e-01 +-7.9410661185668472e+00 +4.2154859118850213e-01 +4.2277351216336395e-01 +-2.6634850279595264e+00 +4.2201701823184068e-01 +4.2365593255088907e-01 +-2.6660236289889072e+00 +4.7310318314372796e-01 +4.4105289406028503e-01 +-2.6864471370134577e+00 +6.0234364136019369e-01 +3.2346698814445424e-01 +-2.7633760823806930e+00 +6.1233761771120676e-01 +3.3387876108794590e-01 +-2.7713312513179842e+00 +1.8288697476883213e+00 +3.5017773540866187e-01 +-4.4541679232099396e+00 +9.0488563096010233e-01 +-4.7638615755217412e-02 +-3.0965973091449301e+00 +7.5394738192214417e-01 +1.7893252538153356e-01 +-2.9116758996776664e+00 +7.8043926143302367e-01 +-4.4779929788381433e-02 +-2.9254178376674664e+00 +1.0259678964986856e+00 +1.3681678319843801e-01 +-3.2161857959803664e+00 +6.9633964188785891e-01 +1.2325095314560672e-01 +-2.8446027300377317e+00 +3.8439558956799513e+00 +5.0541474106067086e-01 +-7.9068259433725476e+00 +3.8439558956799513e+00 +5.0541474106067086e-01 +-7.9068259433725476e+00 +1.0742841905676430e+00 +1.1115373659973928e-01 +-3.2717205478895917e+00 +9.6093217026630107e-01 +3.2673226217529222e-01 +-3.1381565086617975e+00 +9.3844950721491949e-01 +1.4848752238746946e-01 +-3.1229882754749387e+00 +9.4769137531888215e-01 +3.1287423323817665e-01 +-3.1196918300035206e+00 +9.5745250569569640e-01 +3.1974786757312140e-01 +-3.1314350129088497e+00 +7.7220794506364909e-01 +5.8843712291589086e-02 +-2.9213189602062384e+00 +7.8349648519755399e-01 +1.2699179206041575e-01 +-2.9329795169994481e+00 +5.8616235134966921e-01 +3.3878139466936580e-01 +-2.7500073972136967e+00 +1.3615492516441019e+00 +1.9527492280767553e-01 +-2.3063419060293384e+00 +4.4319744442826436e-01 +4.1058737852403998e-01 +-2.6613235560674844e+00 +4.3064847823899077e-01 +3.6105610842233382e-01 +-2.6591698786293345e+00 +1.3157081933879768e+00 +1.7869856115129160e-01 +-2.4332116622813587e+00 +1.3242169296484612e+00 +2.5952620550285754e-01 +-2.4365967153570471e+00 +1.3242169296484612e+00 +2.5952620550285754e-01 +-2.4365967153570471e+00 +1.3279341268933971e+00 +1.2821014464540095e-01 +-2.4157226007009700e+00 +4.4525118542243503e-01 +3.3219833922682890e-01 +-2.6577610181857407e+00 +1.3820874181315324e+00 +2.2832218499307011e-01 +-2.6002465044913312e+00 +3.8456457315031463e+00 +4.8324197668528895e-01 +-7.9087054832656865e+00 +3.8755169552951148e+00 +4.9254547107977392e-01 +-7.9439022697770385e+00 +3.7542094811518565e+00 +2.9422745881468121e-02 +-7.5685692736216570e+00 +1.0297968926407817e+00 +2.3499652336998947e-01 +-3.2236805205688590e+00 +7.0274145376973240e-01 +1.6281082363559263e-01 +-2.8534979552042907e+00 +6.7563536198593432e-01 +2.0946460212873175e-01 +-2.8418178506063878e+00 +9.1123494296973961e-01 +-6.8026378439984464e-02 +-3.0902920395695830e+00 +8.6521290655426475e-01 +3.3635989813600956e-02 +-3.0221856268594025e+00 +9.4537843136864907e-01 +2.7838099634565949e-01 +-3.1275985882864563e+00 +5.9474914920300559e-01 +1.5281170730698121e-01 +-2.7485566141525397e+00 +1.2384987877558029e+00 +1.2071531027616515e-01 +-3.5066210077419067e+00 +7.2497143243221973e-01 +1.9833390585493277e-01 +-2.8902999609691742e+00 +9.1628891217254993e-01 +1.8627969493080588e-02 +-3.0882429446363568e+00 +8.9785476731852842e-01 +2.1364351318137900e-01 +-3.0723192654371547e+00 +9.5410066618288691e-01 +2.6312827505987185e-01 +-3.1370611128638650e+00 +5.1616822481618829e-01 +3.5019144658146700e-01 +-2.6849114418149478e+00 +5.0735573706889692e-01 +2.3620742053776722e-01 +-2.6824567044922767e+00 +1.3373734838307392e+00 +1.2327258573703322e-01 +-2.3534854881057128e+00 +7.9036351182012132e-01 +9.7333950682542927e-02 +-2.9346583447002654e+00 +5.6447514872477322e-01 +3.4083487798184936e-01 +-2.7253905156459846e+00 +4.2971130770546628e-01 +3.9485576244111337e-01 +-2.6534310002440029e+00 +4.4840697483526976e-01 +3.1149091303775467e-01 +-2.6613961903098802e+00 +4.7861294493137174e-01 +8.4370324499462759e-02 +-2.6609001262515468e+00 +4.4911722355858064e-01 +3.1739194420485928e-01 +-2.6634912876955399e+00 +1.3281342385926156e+00 +1.8771919198013656e-01 +-2.3507369779375988e+00 +8.2745925685639887e-01 +-2.6425248585842560e-02 +-2.9785590334192391e+00 +6.7926864516209984e-01 +1.1317651511873977e-01 +-2.8342731080556289e+00 +7.2083941602606250e-01 +1.8290515402342308e-01 +-2.8876356330095883e+00 +6.4406009219061944e-01 +2.6930216065949353e-01 +-2.7979393544347739e+00 +6.7964301513458814e-01 +2.8206446733548685e-01 +-2.8366488502129412e+00 +7.9926614330316348e-01 +2.4135238471172182e-01 +-2.9463681648318589e+00 +5.7595496386021072e-01 +4.0429722010481228e-01 +-2.7379617986545322e+00 +6.1821017644254816e-01 +2.2799220734240963e-01 +-2.7755102730530279e+00 +1.3665726715284681e+00 +7.5300293374429589e-02 +-2.3073747483798011e+00 +1.3820635662241232e+00 +2.0227739140111539e-01 +-2.2959303288739328e+00 +1.8411251262887540e+00 +5.0587877413860993e-01 +-3.0571261415456155e+00 +1.3380096804331316e+00 +6.9297713347252057e-02 +-2.3506049697157052e+00 +5.5108832794371110e-01 +3.8248124366733044e-01 +-2.7121807843407120e+00 +5.7981731833836203e-01 +1.0157222751853320e-01 +-2.7355544790164972e+00 +4.9258100335823368e-01 +2.2754367815316817e-01 +-2.6793572756455362e+00 +7.7654943037393842e-01 +-6.6173349688976951e-02 +-2.9082425489064736e+00 +1.3250447029559287e+00 +9.1005054504448804e-02 +-2.3728194912734075e+00 +5.7518409446365226e-01 +3.1709914742064882e-01 +-2.7391173317396635e+00 +4.8443043294703075e-01 +1.7241226967043977e-01 +-2.6725775652228640e+00 +6.1234703340921826e-01 +2.3126741593700861e-01 +-2.7719515701436230e+00 +4.5697059147108521e-01 +2.4867608203944139e-01 +-2.6538392081815778e+00 +4.5012329262832879e-01 +2.6504061353830571e-01 +-2.6605536094839581e+00 +6.4078184809250582e-01 +6.2376732975583174e-02 +-2.7912382359765755e+00 +7.3597178601705027e-01 +8.1883329719740064e-02 +-2.8906483915261383e+00 +6.2747733973272701e-01 +9.7353059962633326e-02 +-2.7726254190892248e+00 +6.2642397040135966e-01 +1.0262262096539911e-01 +-2.7725639888975642e+00 +5.3680914094971088e-01 +1.0691853984668943e-01 +-2.6910386973900078e+00 +5.4904708004600400e-01 +1.4264807750462077e-01 +-2.7050917104700956e+00 +5.5859212983449558e-01 +1.7593904304076530e-01 +-2.7186602770607795e+00 +5.0862583457126875e-01 +2.3776798967005544e-01 +-2.6909272676562530e+00 +4.9731262434258544e-01 +2.6717504431315559e-01 +-2.6705994199270444e+00 +4.7750674147121053e-01 +2.8807628092041854e-01 +-2.6455407049638482e+00 +5.5243735661987348e-01 +3.5532094408478965e-01 +-2.7137506115391807e+00 +5.5142658933701238e-01 +3.6750507903148971e-01 +-2.7065716538123135e+00 +9.1299262065456799e-01 +-9.3043933674970936e-02 +-3.0807021815262270e+00 +6.4260962596939153e-01 +1.2770700359408388e-01 +-2.7966546746102470e+00 +5.5975492322432274e-01 +1.4029619642029126e-01 +-2.7174491793350271e+00 +5.1559085423766815e-01 +1.4403389435373098e-01 +-2.6757035994119249e+00 +3.8551701824914288e+00 +4.7520401368249221e-01 +-7.9029495308795603e+00 +9.2199149970388894e-01 +1.9022792730683744e-01 +-3.0841723811196533e+00 +5.1468651186748438e-01 +1.7792942447468404e-01 +-2.6801624971773097e+00 +1.0257125352013678e+00 +2.2832479705378503e-01 +-3.2254918283500817e+00 +1.8072279219712952e+00 +3.5365678277982160e-01 +-4.4592656359571912e+00 +1.3740084838066002e+00 +1.8244840107950694e-01 +-2.3022331695163816e+00 +5.6416947153796537e-01 +2.2306502593218536e-01 +-2.7236269627252194e+00 +5.6707161217969926e-01 +2.3433303821740037e-01 +-2.7207111495847163e+00 +9.0722695231764705e-01 +3.1857093112087531e-01 +-3.0956344755809821e+00 +4.3827490528929725e-01 +2.9050255845604073e-01 +-2.6365929066701845e+00 +5.4186758087665421e-01 +3.1424321636599412e-01 +-2.6995113947769287e+00 +6.2676368153126727e-01 +3.2488440994315587e-01 +-2.7781570608456989e+00 +9.1676947999666869e-01 +3.6803122580697573e-01 +-3.1102848809071704e+00 +5.3604552551599161e-01 +3.6029649426947147e-01 +-2.6979072790580076e+00 +5.1144797571749057e-01 +4.1645371465041819e-01 +-2.6891378424481034e+00 +8.2791125546780342e-01 +-9.4300453722541339e-02 +-2.9780424919542123e+00 +5.4377504251830711e-01 +8.7170017350316403e-02 +-2.6937129860425846e+00 +1.3645833951656483e+00 +7.7984875570477771e-02 +-2.3099031885288226e+00 +1.8430392906322226e+00 +2.0920574570993539e-01 +-4.4402453880474573e+00 +5.3158130098742207e-01 +1.3614952864157695e-01 +-2.6856478413695046e+00 +5.8429215184248173e-01 +1.4269527669852194e-01 +-2.7405104724296083e+00 +1.3270420693544258e+00 +1.5997048016894502e-01 +-2.3925603791383678e+00 +1.0313453120674299e+00 +2.1922417346778891e-01 +-3.2245075949457429e+00 +5.5944439190334616e-01 +1.9483811178700397e-01 +-2.7182106531169778e+00 +4.8880964068801130e-01 +2.6192918165783896e-01 +-2.6750760120536583e+00 +6.2116200021925527e-01 +3.3582862350331866e-01 +-2.7823048282844436e+00 +5.2203579507439224e-01 +3.7361858534256559e-01 +-2.6873511966915791e+00 +5.3518667502828021e-01 +3.9751497484223808e-01 +-2.7004425494302637e+00 +4.7256610906328939e-01 +3.9512921282247770e-01 +-2.6742936495814997e+00 +8.9050656940005524e-01 +-7.5859193221402582e-02 +-3.0632089219677261e+00 +4.3259006507526108e+00 +-5.0605642274257553e-02 +-8.4008065353628343e+00 +3.7630529266610671e+00 +8.2337623907655741e-02 +-7.5930153608260094e+00 +5.6801472995845292e-01 +1.5418796335269788e-01 +-2.7222660455373942e+00 +8.4786566069576408e-01 +1.8489555694649271e-01 +-3.0014449380743486e+00 +5.2540413904694527e-01 +2.5397542975425008e-01 +-2.6912159823278645e+00 +4.7772763475947949e-01 +3.0709503040384606e-01 +-2.6726309350818442e+00 +4.6348188444998134e-01 +3.9650188015159860e-01 +-2.6748733152297750e+00 +-9.8859929148977532e-01 +5.7668294483808780e-01 +-2.4210675867939795e+00 +1.3420587761856253e+00 +2.2235137642081823e-01 +-2.3646190863493461e+00 +-8.8106414731402716e-01 +4.3386033641193356e-01 +-2.5001000476501196e+00 +-9.9271562980550998e-01 +4.3745440362609145e-01 +-2.4216997907790416e+00 +6.6612223875106513e-01 +4.2213008157219922e-01 +-2.8592796640130453e+00 +5.0102615268200967e-01 +4.0649962109626925e-01 +-2.6996715358220000e+00 +-4.8025182489241619e-02 +2.0664554555605638e-01 +-6.6384466842619649e-01 +-4.8025182489241619e-02 +2.0664554555605638e-01 +-6.6384466842619649e-01 +-1.2009993033978708e+00 +1.7089833162307735e-01 +-2.3805459618556175e+00 +6.4060289722916675e-01 +3.1426329511684886e-01 +-2.8579018022245464e+00 +8.4726142405032867e-01 +3.5621545684528511e-01 +-3.1919259404881055e+00 +5.8506410557699451e-01 +3.3294269728534009e-01 +-2.7467910711669861e+00 +-1.3606518586645546e+00 +3.6952411587619022e-01 +-2.4181318239755965e+00 +-8.9217900787960680e-01 +6.2210314345612061e-01 +-2.4880338780102407e+00 +-1.0044278487858762e+00 +6.2544231042085796e-01 +-2.4240386641299052e+00 +7.6080809384588566e-01 +7.7734622131951356e-02 +-2.8910603244957946e+00 +1.3493020260021771e+00 +1.8733621636978298e-01 +-2.4634428679969345e+00 +1.3302650584694176e+00 +2.0837803628118767e-01 +-2.4409454847693648e+00 +8.9413803821288063e-01 +2.6902475708860651e-01 +-3.0683817374748896e+00 +1.3322682734434290e+00 +2.4259544603125488e-01 +-2.4454615512781808e+00 +1.3877973337557656e+00 +2.7217636850459642e-01 +-2.3352735724897911e+00 +-7.9094469520563060e-01 +3.2593724326412477e-01 +-2.5940650111702590e+00 +-9.9589865960727497e-01 +4.1636126451846928e-01 +-2.4241034093779237e+00 +-7.9053622907830245e-01 +6.1670573585951738e-01 +-2.5817721056989220e+00 +-8.6262082611924262e-01 +6.1988568349118522e-01 +-2.5102645836264545e+00 +-9.8768870456435687e-01 +6.2840325121112683e-01 +-2.4465800397252018e+00 +-1.1101960341219981e+00 +6.2871935990495220e-01 +-2.3846917289942158e+00 +-8.6316594922355250e-01 +6.7618865558850438e-01 +-2.5775365970253414e+00 +-1.3327487439339412e+00 +6.5916636887143754e-01 +-2.4259748987627012e+00 +-1.3327487439339412e+00 +6.5916636887143754e-01 +-2.4259748987627012e+00 +-1.0554444142284709e+00 +6.5484158834094619e-01 +-2.4128418163506038e+00 +-1.3667028331623969e+00 +6.8168537881455504e-01 +-2.4427977179235190e+00 +-1.0688107647841234e+00 +6.8650251817189845e-01 +-2.4537713174413964e+00 +-9.7431268386997438e-01 +7.2245150306116590e-01 +-2.4475236486919432e+00 +-1.2093959509268000e+00 +8.5195865077142807e-01 +-2.4495416536148160e+00 +-9.7853158115892325e-01 +4.9855645112088162e-02 +-2.4250119451280883e+00 +7.1894300264391497e-01 +8.4017715208205862e-02 +-2.8845035085693311e+00 +-1.2116359310443106e+00 +1.3070625731670849e-01 +-2.3777082417965572e+00 +-1.1993796738018370e+00 +1.4662472335790422e-01 +-2.3883512032192855e+00 +6.8850645746303940e-01 +1.9419674447401661e-01 +-2.7831289181975087e+00 +1.1308010644874731e+00 +2.3772530226588004e-01 +-3.3713508598137616e+00 +-1.2966564723999732e+00 +1.7906478271989060e-01 +-2.3954736867614925e+00 +5.7800971906404530e-01 +1.9621432529609320e-01 +-2.7171425257681618e+00 +5.7800971906404530e-01 +1.9621432529609320e-01 +-2.7171425257681618e+00 +-1.1562486032127075e+00 +1.9447444027301633e-01 +-2.3839686567865055e+00 +-1.1562486032127075e+00 +1.9447444027301633e-01 +-2.3839686567865055e+00 +-1.3084734436186787e+00 +1.9642572080281950e-01 +-2.3950521962109850e+00 +-1.3074324021698294e+00 +1.9595620020554744e-01 +-2.3933319941696984e+00 +-7.5374450704394103e-01 +2.2149137373149061e-01 +-2.6687210067915426e+00 +-7.5346550643916566e-01 +2.2067652782647848e-01 +-2.6672744698647755e+00 +7.3748212403022273e-01 +2.6761893208752541e-01 +-2.8913825776355009e+00 +5.4570539907702054e-01 +2.7732744333541826e-01 +-2.6948268228698686e+00 +1.3409650728313549e+00 +2.7017227192240884e-01 +-2.4651561935225206e+00 +1.3347756578714329e+00 +2.7136287294514394e-01 +-2.3930927897628269e+00 +-7.7714550971367435e-01 +3.2709860549679237e-01 +-2.6260666536611494e+00 +5.2279482697981150e-01 +3.3494226952968620e-01 +-2.6601923963025893e+00 +5.9634800628711271e-01 +3.8126552268910963e-01 +-2.7608323718584908e+00 +-7.5864320657035766e-01 +3.9072781428484787e-01 +-2.6535339258883424e+00 +4.8662631630133940e-01 +4.2350173860869267e-01 +-2.6684659386133576e+00 +-9.3789608259571211e-01 +3.9967850546275735e-01 +-2.4620885415052651e+00 +-1.0098829752824039e+00 +4.0133124878479465e-01 +-2.4192562543229399e+00 +-7.0232136095393616e-01 +6.3928266287935054e-01 +-2.8488212481279667e+00 +-1.2922523565338799e+00 +5.6349841996446415e-01 +-2.3982153469253040e+00 +-7.8731097523785754e-01 +6.4477918346418617e-01 +-2.6163480758486877e+00 +-1.0835397644892595e+00 +6.9411469534967973e-01 +-2.4360839274919375e+00 +-1.2202963888310914e+00 +6.9932891111342566e-01 +-2.4124953096794024e+00 +-1.1753870193178995e+00 +7.1605564881139960e-01 +-2.3938752485828778e+00 +-1.1753870193178995e+00 +7.1605564881139960e-01 +-2.3938752485828778e+00 +-1.1769908368805189e+00 +7.9746143513936751e-01 +-2.4427189689728008e+00 +8.0367038177728833e-01 +3.1305407962118080e-02 +-2.9451548502880365e+00 +-1.1107737436712277e+00 +3.6557782134803644e-02 +-2.3860176707346752e+00 +-8.8367376941343123e-01 +6.6581317312498098e-02 +-2.4845468461244011e+00 +-9.8730126376250649e-01 +6.9512271498874290e-02 +-2.4146737231153024e+00 +-1.1956175708597305e+00 +7.5996662962953612e-02 +-2.3762554163076159e+00 +8.2607997888743179e-01 +9.2821160149096707e-02 +-2.9699596703145645e+00 +-8.6562214216805800e-01 +9.0104038293967362e-02 +-2.5236664604512282e+00 +-9.2309774504225273e-01 +9.2325311219031425e-02 +-2.4716770086012017e+00 +1.1085465463518558e+00 +1.2713626311957540e-01 +-3.3821821780246943e+00 +-9.7760065258349604e-01 +9.0067163015201859e-02 +-2.1521966716785492e+00 +-1.1955455231128103e+00 +1.0039154315571967e-01 +-2.3778216196982420e+00 +1.2384191221875238e+00 +1.4012996261981042e-01 +-3.5152273810359174e+00 +-1.1968958119919864e+00 +1.1411172194804485e-01 +-2.3823822107699444e+00 +-9.0594096561097337e-01 +1.1914734263619109e-01 +-2.4811356757472351e+00 +7.9109758081798898e-01 +1.3819914404731190e-01 +-2.9338850162975434e+00 +9.3396308277210960e-01 +1.5261398636786977e-01 +-3.1128215587365289e+00 +9.3396308277210960e-01 +1.5261398636786977e-01 +-3.1128215587365289e+00 +1.0499528943927916e+00 +1.6625368388130185e-01 +-3.2496253706880545e+00 +1.0933228474102734e+00 +1.7152823555665561e-01 +-3.3011244902922030e+00 +8.2391679932098305e-01 +1.8025768321639457e-01 +-2.9711196566341038e+00 +6.9989886262993040e-01 +1.7642324790989000e-01 +-2.8366280812670017e+00 +1.2228649142733292e+00 +2.4166104127546395e-01 +-3.4921493894008417e+00 +-9.8572860325793821e-01 +1.9045589918357017e-01 +-2.4240578541442872e+00 +-1.0115050896115207e+00 +1.9101791625841594e-01 +-2.4114089496987692e+00 +1.0305413609016898e+00 +2.5402021340719300e-01 +-3.2199714149143768e+00 +5.8486012194687187e-01 +2.3102439012058731e-01 +-2.7380849313833231e+00 +5.8380168485373629e-01 +2.2758740380369794e-01 +-2.7381729683574685e+00 +5.3591787872989116e-01 +2.4119652072048819e-01 +-2.6816821056156268e+00 +6.8953064984049417e-01 +2.6852410057712384e-01 +-2.8414148243290200e+00 +1.3493476835223517e+00 +2.5696682718340069e-01 +-2.5670321386075359e+00 +-1.2504319754653050e+00 +2.4979052653363870e-01 +-2.3760581334462416e+00 +5.2400516662370000e-01 +3.2193018035712273e-01 +-2.6924658399837234e+00 +-1.0597442951116374e+00 +3.0509210310433754e-01 +-2.4039957114613344e+00 +-1.2765476079996110e+00 +3.0682752295500498e-01 +-2.3842595973703751e+00 +-1.1554565436423034e+00 +3.0710120107362299e-01 +-2.3897791115508062e+00 +6.1985691042269275e-01 +3.6081212370556970e-01 +-2.7749655418436867e+00 +-7.2734870828037579e-01 +3.6653295460287760e-01 +-2.7161049262125077e+00 +5.6269680174629488e-01 +3.7013900186905468e-01 +-2.7177245849787712e+00 +-7.7816618547425920e-01 +3.9103516550153516e-01 +-2.6023671223814198e+00 +-7.2369780212106549e-01 +4.1902481309311157e-01 +-2.7068983526393460e+00 +-1.1092117513194710e+00 +3.9105601909690768e-01 +-2.3942713720329727e+00 +-1.3381614159876651e+00 +4.0806852227920609e-01 +-2.4064630172700845e+00 +-4.6193479585808987e-02 +9.4760202317069095e-02 +-6.5723651602372779e-01 +-1.1140350689172609e+00 +4.0418605220503606e-01 +-2.3832836859051771e+00 +-1.0293191722994552e+00 +4.1579395242387990e-01 +-2.4169286671890768e+00 +-1.1101868868596305e+00 +4.1797462996989276e-01 +-2.3944123309857250e+00 +-7.5901754968266810e-01 +4.7077323329257803e-01 +-2.6595605852378004e+00 +5.2720103566605547e-01 +5.0043997482810931e-01 +-2.8009836363966358e+00 +-7.3657136838199433e-01 +4.9576240587182008e-01 +-2.6911463805149496e+00 +-1.4204891135437632e+00 +5.1555208868807967e-01 +-2.4114139098728491e+00 +-8.9805300084000594e-01 +5.5618354324375296e-01 +-2.4762507553976207e+00 +-1.1980860771471545e-01 +1.4358741016051565e-01 +-7.2056787629182506e-01 +-8.0559202789401918e-01 +5.9305259965055013e-01 +-2.5820811100013050e+00 +-7.7313609713111409e-01 +6.1616411085254097e-01 +-2.6072219430422043e+00 +-7.7265485793987576e-01 +6.1637029799779230e-01 +-2.6052349295075770e+00 +-7.9151686538194521e-01 +6.9581064006829663e-01 +-2.5964486123317032e+00 +-1.2921721233281840e+00 +6.7357320112314201e-01 +-2.4055904134088255e+00 +7.6088298189933834e-01 +-5.6100759642566923e-02 +-2.9093869238155530e+00 +3.1729900395706490e-01 +-5.2563084143901484e-03 +-7.6370222752761541e-01 +-1.1159911236823583e+00 +2.3362331394668024e-02 +-2.3821546058398444e+00 +7.3398578922978397e-01 +8.4441253036814698e-02 +-2.8981517559501015e+00 +9.6307536592085652e-01 +1.1502788473044492e-01 +-3.1461073208888917e+00 +7.0853862356269304e-01 +1.0603938860270398e-01 +-2.8578183096807561e+00 +7.1089531148357521e-01 +1.0607515780566454e-01 +-2.8672264828163869e+00 +9.1377065978755512e-01 +1.1815946378030198e-01 +-3.0904072449511855e+00 +7.0628539312402583e-01 +1.2240913880231248e-01 +-2.8560648939286568e+00 +7.0628539312402583e-01 +1.2240913880231248e-01 +-2.8560648939286568e+00 +1.3387079173817855e+00 +1.0215880282248738e-01 +-2.3283221879623328e+00 +1.2710345798723817e+00 +1.6071009434304293e-01 +-3.5634479459541457e+00 +1.2060549412011179e+00 +1.6247640688920983e-01 +-3.4585450820011530e+00 +1.2060549412011179e+00 +1.6247640688920983e-01 +-3.4585450820011530e+00 +1.1348465654529711e+00 +1.6790039263575421e-01 +-3.3672498559004449e+00 +6.1327842839469826e-01 +1.5301979991053635e-01 +-2.7730002217444536e+00 +-1.4170743220087174e+00 +1.8464858463837741e-01 +-2.4116392190611458e+00 +-1.2423768997454359e+00 +1.8287536713740649e-01 +-2.3620176121616590e+00 +-7.9223996394050045e-01 +1.9566862102174296e-01 +-2.5777712298327384e+00 +-1.2186107145550675e+00 +1.8356291156657650e-01 +-2.3683753925074038e+00 +5.4496712363807209e-01 +2.0493017430381349e-01 +-2.7072995810305489e+00 +7.3070621471001274e-01 +2.2061789827933295e-01 +-2.8867291164257773e+00 +-8.7316931893499172e-01 +2.0052611821590524e-01 +-2.5017209438926278e+00 +-9.0163720755818388e-01 +2.0113689955861319e-01 +-2.4829052016712305e+00 +-7.6226994743143506e-01 +2.1305316297310736e-01 +-2.6430656783156046e+00 +1.1395059574972644e+00 +2.7259993051866832e-01 +-3.3844971879900179e+00 +-9.8414606566445417e-01 +2.0445211600510199e-01 +-2.4308581320617737e+00 +-1.0190817978099320e+00 +2.0522117786401978e-01 +-2.4223918093140693e+00 +-1.1262549296491784e+00 +2.0747534656654479e-01 +-2.3775076564917406e+00 +-1.2566963892592560e+00 +2.0999517155435010e-01 +-2.3724084648567807e+00 +5.5037272129036596e-01 +2.2867158640529436e-01 +-2.7142501780899204e+00 +-1.2040804159383749e+00 +2.0990278424094119e-01 +-2.3659293822165455e+00 +6.2000385080797216e-01 +2.3780627788895364e-01 +-2.7712287184900841e+00 +6.5858785614941351e-01 +2.5271326128711524e-01 +-2.8013728868826950e+00 +6.4527713158892963e-01 +2.5225015906706522e-01 +-2.8011378140275123e+00 +-1.1930383214463560e+00 +2.3589213416289811e-01 +-2.3824536156351184e+00 +6.4916860563443901e-01 +2.6720624910012153e-01 +-2.7919149311776827e+00 +5.3412046470944008e-01 +2.6076693678610469e-01 +-2.6899099538310569e+00 +6.6992807849451741e-01 +2.8356925658040621e-01 +-2.8231628156533395e+00 +5.7239170791778926e-01 +2.7744182846202481e-01 +-2.7269539419615545e+00 +9.1909804229302938e-01 +3.2303125598699312e-01 +-3.0900317438197153e+00 +-7.8335016411362013e-01 +3.0748704151187234e-01 +-2.8795131815123733e+00 +8.4277394823261387e-01 +3.7136879239328352e-01 +-3.1497695410530868e+00 +-9.8146051786222777e-01 +3.0157907082421875e-01 +-2.4295560481887231e+00 +-1.3044810324529215e+00 +3.0701217367244010e-01 +-2.3935477791461226e+00 +-1.1160101383200256e+00 +3.0462432086470254e-01 +-2.3748550016332119e+00 +-1.1734746124945898e+00 +3.0570419770563506e-01 +-2.3865533757578250e+00 +-1.1742731374804498e+00 +3.1691534282188383e-01 +-2.3844641379322025e+00 +-1.2031646074743023e+00 +3.1929798717976371e-01 +-2.3681516666948004e+00 +4.9048738215639698e-01 +3.4541944762348209e-01 +-2.6631421276282734e+00 +-7.1222562924437727e-01 +3.6891223222643721e-01 +-2.7762428570352005e+00 +-1.0179248705712520e+00 +3.9076503627752945e-01 +-2.4214912642944966e+00 +5.1476644928799786e-01 +4.2402667182381626e-01 +-2.6882793814003376e+00 +-1.0795516885390632e+00 +4.1662701413590536e-01 +-2.4029605864669636e+00 +-1.2818216213523981e+00 +4.1815987609488425e-01 +-2.3958604120004416e+00 +-9.7872509587986622e-01 +4.2559036758893398e-01 +-2.4393356599829152e+00 +-9.7944895847182700e-01 +4.2560043433765149e-01 +-2.4409541804296548e+00 +-9.9436063218945780e-01 +4.8509434359065212e-01 +-2.4282598985994648e+00 +-7.3818200393446576e-01 +5.8994612293803328e-01 +-2.6975575911921252e+00 +-8.0692212611666936e-01 +5.6738515355940944e-01 +-2.5791224538221340e+00 +-7.6827263245556587e-01 +5.7921722273010323e-01 +-2.6305550774384003e+00 +-7.7124581007730786e-01 +5.7954544083182191e-01 +-2.6382018564747658e+00 +-1.1641459041302602e+00 +6.6314353137053494e-01 +-2.3990196797824193e+00 +-1.4233931569251108e+00 +6.7423036311372275e-01 +-2.4141498399747805e+00 +-1.0224057709827836e+00 +6.6876174987768278e-01 +-2.4174415217549416e+00 +-1.1048634343124588e+00 +6.7601920059486587e-01 +-2.4090602936558838e+00 +-1.2358224969924769e+00 +7.2132113710460544e-01 +-2.3970540012635659e+00 +-1.2358224969924769e+00 +7.2132113710460544e-01 +-2.3970540012635659e+00 +-9.6779117266471504e-01 +8.1668600635561861e-01 +-2.6154896579070961e+00 +-1.1948085431905640e+00 +7.5883281096162103e-01 +-2.3990089827787000e+00 +7.5713153101212549e-01 +-1.8337903501801200e-02 +-2.9309302099775594e+00 +-9.8726595677665185e-01 +8.7096931501776699e-03 +-2.4315873074567400e+00 +7.3985448821021815e-01 +7.0129778442276788e-02 +-2.8922147467010006e+00 +9.0110570606313212e-01 +1.0677565025702490e-01 +-3.0854604463604050e+00 +1.0312279140496532e+00 +1.1364719231717159e-01 +-3.2182697958662065e+00 +1.0055260188264687e+00 +1.1360585310874088e-01 +-3.2113298373610304e+00 +1.0052825039611550e+00 +1.1393827589663789e-01 +-3.2100282030599976e+00 +6.4965934039901363e-01 +9.9982545474846959e-02 +-2.7948609568729719e+00 +1.1406412301415905e+00 +1.2595566540481679e-01 +-3.3928519056800006e+00 +6.6446588592528966e-01 +1.0900430690224512e-01 +-2.8227376394959549e+00 +1.2762469374997332e+00 +1.4166483776072827e-01 +-3.5562220873066313e+00 +1.0868510508877713e+00 +1.3740240812989768e-01 +-3.2891569338377047e+00 +7.5409098457110235e-01 +1.2123087254214183e-01 +-2.9119896488218471e+00 +1.1838680453751851e+00 +1.4880650708723062e-01 +-3.4322223886132299e+00 +6.6507308057842951e-01 +1.2584418290520316e-01 +-2.8267493213768553e+00 +1.3691764818844121e+00 +1.0789146872507557e-01 +-2.3304083229107526e+00 +5.2445189826062000e-01 +1.3697263546521210e-01 +-2.6902169284273851e+00 +7.5335588368735140e-01 +1.6270183660425272e-01 +-2.9126103831090395e+00 +7.5433107402312749e-01 +1.6303736678660199e-01 +-2.9166922495382597e+00 +7.5138548441603881e-01 +1.7855666593484282e-01 +-2.9025967743287011e+00 +9.5163550257977925e-01 +1.9787731195724342e-01 +-3.1299877262776636e+00 +1.1382197768058406e+00 +2.1636564227728272e-01 +-3.3720662836894428e+00 +1.1366170298825151e+00 +2.1596010369447674e-01 +-3.3671555396719142e+00 +9.2770094115334989e-01 +2.0111673553653464e-01 +-3.0960913554036367e+00 +6.6097126491218849e-01 +1.8264612328820767e-01 +-2.8108019209178594e+00 +6.6044272035771623e-01 +1.8312452389743827e-01 +-2.8099375133866915e+00 +9.5832528739986178e-01 +2.1019754073284622e-01 +-3.1200915070486492e+00 +-9.9436385269950511e-01 +1.7274902631049990e-01 +-2.4243469777717270e+00 +-1.0141799973361065e+00 +1.7478994429964093e-01 +-2.4411375190707387e+00 +1.1771490233598443e+00 +2.4429003906589533e-01 +-3.4356795155382498e+00 +1.1769040334545025e+00 +2.4428490786779794e-01 +-3.4353526797220404e+00 +7.3751559883336415e-01 +2.0837473882743945e-01 +-2.8763251950862956e+00 +-8.0704899989152246e-01 +1.9662090936476648e-01 +-2.5708072289728960e+00 +-7.6737175005057301e-01 +2.0381435868157424e-01 +-2.6338952314921023e+00 +8.4422270711553216e-01 +2.2825580198197593e-01 +-2.9888785852247910e+00 +6.7287363073435835e-01 +2.1823235963659307e-01 +-2.8385374601573932e+00 +-9.3951353289356043e-01 +2.0379364354943980e-01 +-2.4526841196238496e+00 +-1.1116930073711220e+00 +2.0678655541940094e-01 +-2.3911220241514246e+00 +8.5098049411119669e-01 +2.5014502531542726e-01 +-2.9981142426549687e+00 +8.6812464124274313e-01 +2.5796562854262212e-01 +-3.0196002071334065e+00 +-1.0724136174241958e+00 +2.1674960002360683e-01 +-2.3995110935486066e+00 +5.7486695760371487e-01 +2.4177125573737732e-01 +-2.7235667417420801e+00 +1.3541688206919211e+00 +2.3163151344937913e-01 +-2.5320761791340014e+00 +8.1319786349059031e-01 +2.6860147163149972e-01 +-2.9525818414595300e+00 +7.9415614232026910e-01 +2.6646189182137064e-01 +-2.9423221752126585e+00 +4.8238641386503156e-01 +2.3945736711712506e-01 +-2.6640989915800164e+00 +4.8238641386503156e-01 +2.3945736711712506e-01 +-2.6640989915800164e+00 +6.8505470539830648e-01 +2.6274462399228016e-01 +-2.8130305798257642e+00 +8.6112605532251807e-01 +2.8415397858442015e-01 +-3.0076420864701441e+00 +5.2318904524437604e-01 +2.7821666319371080e-01 +-2.6801644265370590e+00 +5.9158515173175596e-01 +2.8732546710486900e-01 +-2.7535593587625553e+00 +5.6884831988010187e-01 +2.8920827226532847e-01 +-2.7181192535178713e+00 +-7.7043527896443065e-01 +3.1727144370175109e-01 +-2.8880274858860142e+00 +6.1252118114142051e-01 +3.0817654388448962e-01 +-2.7725167738510033e+00 +-7.7310879467696025e-01 +3.0179406924574281e-01 +-2.6281673290771232e+00 +-7.9311836392323709e-01 +3.0270984323359695e-01 +-2.5819258361847961e+00 +-1.3068830469765080e+00 +2.9081408697095285e-01 +-2.3986852495622801e+00 +1.3328482670584660e+00 +2.9839064397216269e-01 +-2.4779616904071369e+00 +-8.7227749615379169e-01 +3.0825250274045224e-01 +-2.5048831315446418e+00 +-8.9813425793338286e-01 +3.0952809110003238e-01 +-2.4877513264347835e+00 +-7.8366834447635181e-01 +3.9301341344101753e-01 +-3.1212991730967272e+00 +5.0965464181421227e-01 +3.3110496808867346e-01 +-2.6849996055783967e+00 +-8.8497957193032106e-01 +3.1552198417194816e-01 +-2.4937093588017354e+00 +-9.4638342959266242e-01 +3.1085773062528743e-01 +-2.4552812457269120e+00 +-9.8557349863749810e-01 +3.1234438610552356e-01 +-2.4322931613008798e+00 +-1.0128210805686324e+00 +3.1292439333063760e-01 +-2.4183424253703962e+00 +-1.1238277608474301e+00 +3.2618456892715281e-01 +-2.3900735785017009e+00 +6.4278506362650933e-01 +3.8463372349891245e-01 +-2.8334025726836889e+00 +5.8548286712595654e-01 +3.9136321713675681e-01 +-2.7392331172959512e+00 +5.8162278792041688e-01 +3.8901829177432173e-01 +-2.7231670268249775e+00 +4.6950400245439283e-01 +3.8609885308831726e-01 +-2.6686545606099306e+00 +5.9692525774414762e-01 +4.0339686828307703e-01 +-2.7520145325949339e+00 +5.2745619335258376e-01 +4.1975769018944264e-01 +-2.6912349148308539e+00 +-8.0864429630423229e-01 +4.1880093710534594e-01 +-2.5759289502196054e+00 +-9.0483587595404247e-01 +4.2350595057699897e-01 +-2.4887744421229194e+00 +-1.3694600259955270e+00 +4.1819041236748727e-01 +-2.4041314160827456e+00 +-9.4827509151260136e-01 +4.2495783974628260e-01 +-2.4617837340817483e+00 +-1.0571932611768411e+00 +4.1704952355282987e-01 +-2.4000688666126280e+00 +-1.0695164819179515e+00 +4.2885540616621387e-01 +-2.4117158490222437e+00 +-9.8936292514839030e-01 +4.5955177784579548e-01 +-2.4286739479185235e+00 +-1.0001822467177863e+00 +4.6003756440542082e-01 +-2.4254428903193253e+00 +-7.1696349780141855e-01 +5.7498953623936111e-01 +-2.7568008784945408e+00 +-4.7620581225059522e-02 +1.2505073802235284e-01 +-6.5989051392271192e-01 +-1.0085870990854995e+00 +5.5918200132441398e-01 +-2.4261230879966291e+00 +-8.0650811234659348e-01 +6.5432154775271756e-01 +-2.5893645067276614e+00 +-8.9989660566332563e-01 +6.5952677366901780e-01 +-2.4978470518169416e+00 +-9.3984512237065410e-01 +6.7073335680295521e-01 +-2.4775084158039435e+00 +-1.0596002634061390e+00 +6.7659946849149299e-01 +-2.4287475896448081e+00 +-1.1176228753807371e+00 +7.0655084287112668e-01 +-2.4109757107919334e+00 +3.2402986920452198e-01 +-2.3574170330171160e-02 +-7.6451045069549428e-01 +7.8812486373467849e-01 +-6.7090073776799250e-02 +-2.9489530040837617e+00 +7.9249254339082731e-01 +-5.5438517486804360e-02 +-2.9423052063558153e+00 +9.0045751208567149e-01 +-5.6004870032072836e-02 +-3.0768701637343674e+00 +3.0650688349357919e-01 +3.4153616056099814e-03 +-7.6536757501735087e-01 +-1.1752274928097088e+00 +2.7444750008353346e-02 +-2.3847283553870766e+00 +8.8668654099583633e-01 +4.0081421590902132e-02 +-3.0445648057254791e+00 +8.5507855893894602e-01 +4.0042318384039169e-02 +-3.0137568758267768e+00 +-1.1287350802763714e+00 +4.3937312968955762e-02 +-2.3731132757115025e+00 +-8.3709546551561542e-01 +5.4904254614738773e-02 +-2.5341030032800913e+00 +-9.4087219663024202e-01 +5.8021444000353001e-02 +-2.4488197843403117e+00 +6.8151789188095646e-01 +6.3934340633539921e-02 +-2.8348833998088301e+00 +-1.0631729620475876e+00 +6.2201395927139476e-02 +-2.3926834305873359e+00 +-1.1605000819938298e+00 +6.4065102439634480e-02 +-2.3780893643561893e+00 +-9.3960968727752170e-01 +6.5200842202073603e-02 +-2.4467345748457263e+00 +6.4936350036309709e-01 +7.3256523840817142e-02 +-2.7974458372367557e+00 +-1.2112380692028859e+00 +7.1573442506952759e-02 +-2.3691442857995386e+00 +9.1968678909120127e-01 +8.6382744808399720e-02 +-3.1184190546213912e+00 +9.9237050614515487e-01 +9.1441324405211202e-02 +-3.1960104679122607e+00 +9.9364933519110865e-01 +9.1990253723406842e-02 +-3.2012770531195947e+00 +-9.8281575444975167e-01 +8.2733463719105380e-02 +-2.4267033213337106e+00 +-8.7650802824368568e-01 +8.6390891442503878e-02 +-2.4983141536702975e+00 +-1.0739896624000340e+00 +8.5479138435654092e-02 +-2.3896015908185047e+00 +-1.0739896624000340e+00 +8.5479138435654092e-02 +-2.3896015908185047e+00 +-1.1091087429107320e+00 +8.6573207637633723e-02 +-2.3816381460107836e+00 +-1.1515275341705131e+00 +8.8882525729314626e-02 +-2.3763249805338966e+00 +-1.1843495219434346e+00 +8.8706355487488661e-02 +-2.3771999860691961e+00 +-9.8840126497912517e-01 +8.9900464043525863e-02 +-2.4301647557287036e+00 +3.1041355646222185e-01 +2.4224453987025569e-02 +-7.6882912067963594e-01 +-8.8636296620539667e-01 +9.2694903906897594e-02 +-2.4890046200590246e+00 +-1.1166393859840302e+00 +9.4199551065636239e-02 +-2.3872498356739675e+00 +1.5593632959602597e+00 +1.5261237028209929e-01 +-3.9829807710251597e+00 +-1.2496164934525658e+00 +1.0140382952035941e-01 +-2.3683529401447623e+00 +7.3858021760045978e-01 +1.1731723124059416e-01 +-2.8916119785988004e+00 +3.1077854745675648e-01 +2.9766449738741999e-02 +-7.7361511128472982e-01 +6.8834534849555773e-01 +1.2000661654670175e-01 +-2.8377774834160783e+00 +1.5813054883880933e+00 +1.7603353373406661e-01 +-4.0095517879273688e+00 +7.9826197320662318e-01 +1.2735918960123102e-01 +-2.9372234057116473e+00 +6.4821964121826847e-01 +1.2072206958350894e-01 +-2.7918905117838526e+00 +1.3711024324116940e+00 +9.9720139221778845e-02 +-2.3071725161636021e+00 +1.3883210521126199e+00 +9.9886451159305459e-02 +-2.2798817958784343e+00 +9.6407431089384232e-01 +1.4358072653337384e-01 +-3.1549502880274192e+00 +1.0404408236426439e+00 +1.5666492489065756e-01 +-3.2359968695774786e+00 +1.1924813833373618e+00 +1.7974094629342127e-01 +-3.4432399455328779e+00 +9.6801671821158819e-01 +1.6382793522652259e-01 +-3.1632044218539934e+00 +1.1158572303518597e+00 +1.8662757154917628e-01 +-3.3436837249803060e+00 +9.2041883114974343e-01 +1.7112458438445327e-01 +-3.0979660145574863e+00 +9.7940958743322937e-01 +1.8197964219058241e-01 +-3.1612858301256015e+00 +1.1735929866030592e+00 +1.9988525980929930e-01 +-3.4114542195611066e+00 +-1.1768444095860682e+00 +1.5196866983062404e-01 +-2.3875404720757367e+00 +-1.1847340775641788e+00 +1.5095011263107211e-01 +-2.3820030544037070e+00 +4.7347268237414264e-01 +1.5900585953343244e-01 +-2.6659200745075511e+00 +1.0375108333142893e+00 +2.0012367254826766e-01 +-3.2271479857309293e+00 +5.2008439278424534e-01 +1.6639656139779033e-01 +-2.6875466001996444e+00 +-7.8986822389246303e-01 +1.7227788263764857e-01 +-2.5851426856250042e+00 +1.1551729465305731e+00 +2.2926762551345464e-01 +-3.3993865748325010e+00 +5.6509181776270034e-01 +1.8986406359428637e-01 +-2.7165292257990550e+00 +9.4976942747419302e-01 +2.2075301767436298e-01 +-3.1280096899686800e+00 +6.7250682117728144e-01 +1.9933662791922874e-01 +-2.8316534742092814e+00 +-7.5755268806524823e-01 +1.9447410124909556e-01 +-2.6406331810089867e+00 +-7.3391279829477607e-01 +2.0224675216054050e-01 +-2.6882739958251847e+00 +1.0804003109348022e+00 +2.5080338779240235e-01 +-3.2763197806235445e+00 +8.0035944023488381e-01 +2.3488769588152389e-01 +-2.9456625142489705e+00 +-7.8794992806747621e-01 +2.1175564923429038e-01 +-2.6002365167290367e+00 +-1.0618516495846884e+00 +1.9980491563747999e-01 +-2.3993051749246153e+00 +-9.0677587536756254e-01 +2.1136745928831460e-01 +-2.4791896446025650e+00 +-1.0677922964332260e+00 +2.0918327734994860e-01 +-2.4126809180997464e+00 +-1.1611902794781970e+00 +2.0941542414512607e-01 +-2.3828792738473106e+00 +-9.7829507857881581e-01 +2.1380469875229102e-01 +-2.4350183663892779e+00 +-1.0217920425903562e+00 +2.1512335163863638e-01 +-2.4139630669893348e+00 +8.3765519706391733e-01 +2.5819429809965294e-01 +-2.9880282126256481e+00 +-1.0377697297828039e+00 +2.1552171713035986e-01 +-2.4120642618049684e+00 +-1.0535051976779697e+00 +2.1649495294440510e-01 +-2.4070905255214909e+00 +-1.4293649269865616e+00 +2.2186137107090309e-01 +-2.4095707999176885e+00 +-1.3065545003546379e+00 +2.2046270904322274e-01 +-2.3951990162504750e+00 +-1.3072883786818019e+00 +2.2074618686475242e-01 +-2.3963955201635745e+00 +5.5937502908206871e-01 +2.3620109313349977e-01 +-2.7173090782006026e+00 +8.5294184601681511e-01 +2.6431715220541879e-01 +-3.0027089205817168e+00 +-1.1826033101532036e+00 +2.1993835604996123e-01 +-2.3805124865445029e+00 +-1.3422566189643017e+00 +2.2764297716063797e-01 +-2.4065333371025570e+00 +6.2753355999550053e-01 +2.4926761237349918e-01 +-2.7810092357910388e+00 +-1.2066054680210472e+00 +2.2608279914307741e-01 +-2.3682050073649989e+00 +-1.2555490078142848e+00 +2.2706009097801400e-01 +-2.3738852213343509e+00 +9.5417969896470933e-01 +2.9472070730611544e-01 +-3.1361885023241700e+00 +1.3551518478205573e+00 +2.4895812825940103e-01 +-2.5892656487676811e+00 +1.3731858540874839e+00 +2.5011168484969337e-01 +-2.5948369921747623e+00 +-7.4758766563393486e-01 +2.7104496350459878e-01 +-2.6792677644952776e+00 +9.2267612579503588e-01 +3.1239982803696692e-01 +-3.0922404976003595e+00 +5.8390020582123048e-01 +2.9736751481433876e-01 +-2.7444966358935394e+00 +5.8517117319648615e-01 +2.9763900456493819e-01 +-2.7502962682185492e+00 +6.2370641394161863e-01 +3.0372084470548266e-01 +-2.7760826837796841e+00 +-1.3864242743662745e+00 +2.8579863000488420e-01 +-2.4090818910873093e+00 +5.4818301242299550e-01 +3.1787895750080480e-01 +-2.7052174837597001e+00 +8.3731544265133273e-01 +3.8209643141483168e-01 +-3.1524882976176323e+00 +-1.0676776244130066e+00 +3.1292884591548836e-01 +-2.3990958306632693e+00 +-1.1051500997567199e+00 +3.3130147079854999e-01 +-2.3961419367690886e+00 +7.2298772918785292e-01 +4.0977420619667887e-01 +-3.0146975462339016e+00 +-1.1343265155016977e+00 +3.3447054318661201e-01 +-2.3828927110438691e+00 +5.6050037200291691e-01 +3.8212144454094354e-01 +-2.7190052472917312e+00 +-1.3264352728554447e+00 +3.5997990471705282e-01 +-2.4011853947283255e+00 +-1.1254896836892494e+00 +3.5745671565481918e-01 +-2.3816798932940535e+00 +-1.1254896836892494e+00 +3.5745671565481918e-01 +-2.3816798932940535e+00 +-1.3145800985810225e+00 +3.7114563670519002e-01 +-2.3985647971259847e+00 +-1.3265510512825718e+00 +3.7154792441456908e-01 +-2.4023506175052072e+00 +5.3938706310017093e-01 +4.1539473121037085e-01 +-2.6941600511947970e+00 +-8.3590231028277884e-01 +4.0196732590499434e-01 +-2.5459125247401864e+00 +-1.1252152406728757e+00 +3.8108806128688144e-01 +-2.3816957730937336e+00 +-8.4319816326490260e-01 +4.0617091581324510e-01 +-2.5371152407490052e+00 +-1.0586716896860022e+00 +4.0970594969281304e-01 +-2.4049983154648582e+00 +4.7467065922077073e-01 +4.4968547694494543e-01 +-2.6750585525898294e+00 +4.2025793753827290e-01 +4.4904069987809486e-01 +-2.6588463417802055e+00 +4.1985580057079391e-01 +4.4847626183934558e-01 +-2.6545228821104718e+00 +-7.1588866602851853e-01 +4.7814961989525151e-01 +-2.7401411551987147e+00 +-1.1479884785438481e+00 +4.2589067115024698e-01 +-2.3897056817891409e+00 +-1.3380790305116925e+00 +4.3260214961658522e-01 +-2.4071592863026554e+00 +-1.1021775966460732e+00 +4.3016594961575633e-01 +-2.3993095821076493e+00 +-1.2434173224217431e+00 +4.3315336240148927e-01 +-2.4011549862747850e+00 +-7.9714547137430503e-01 +4.5954491694966731e-01 +-2.5866390424285344e+00 +-8.4593162005896683e-01 +4.6205101528712761e-01 +-2.5420556473155402e+00 +-8.9117231435765287e-01 +4.6376344210684273e-01 +-2.4917727635243456e+00 +-9.8717884952973389e-01 +4.6779193760059901e-01 +-2.4351621749105057e+00 +-1.0059983043656728e+00 +4.6802447554916343e-01 +-2.4258210209368030e+00 +-1.0605397666388168e+00 +4.9687617922128763e-01 +-2.4160787099452556e+00 +-9.3519859013120810e-01 +5.5600252628141378e-01 +-2.4621593260313359e+00 +-1.0570698024171186e+00 +5.5901817263949682e-01 +-2.4090119746809293e+00 +-7.7766440200107623e-01 +6.0781366042999319e-01 +-2.6155162628968673e+00 +-7.6459997208406816e-01 +6.1336422034161908e-01 +-2.6265776461627452e+00 +-8.0101733175831813e-01 +6.0959242388089019e-01 +-2.5868844072273873e+00 +-8.1959682017694313e-01 +6.1007845287986751e-01 +-2.5615509098601197e+00 +-8.0812918367937148e-01 +6.1706161473179422e-01 +-2.5766474780741748e+00 +-8.0695763604971060e-01 +6.1708469614467798e-01 +-2.5732112454264549e+00 +-1.1554446236431228e+00 +5.8089584605220557e-01 +-2.3912992425827930e+00 +-8.1483183636668521e-01 +6.1687356062731769e-01 +-2.5631171890562139e+00 +-8.1483183636668521e-01 +6.1687356062731769e-01 +-2.5631171890562139e+00 +-8.2307581199818081e-01 +6.1646603428324243e-01 +-2.5517695072677484e+00 +-8.2349751391976933e-01 +6.1773893502801724e-01 +-2.5535836822241653e+00 +-8.5507943879556580e-01 +6.1228383875505865e-01 +-2.5265301363616919e+00 +-8.6509390515954043e-01 +6.1260064410884341e-01 +-2.5179781160028591e+00 +-8.4114266825722250e-01 +6.1817177676801338e-01 +-2.5309055750307747e+00 +-8.5047293951095670e-01 +6.1809195010006934e-01 +-2.5241517850075388e+00 +-8.4842928421079256e-01 +6.1739736697165515e-01 +-2.5182182664967687e+00 +-8.9634895261970093e-01 +6.1437351319546774e-01 +-2.4938249736305025e+00 +-9.4141740376086225e-01 +6.1558458189098131e-01 +-2.4634427090904851e+00 +-9.5139610146574993e-01 +6.1616233971601186e-01 +-2.4541918090483419e+00 +-9.6349902632476214e-01 +6.1649495470821791e-01 +-2.4510450654066340e+00 +-9.2557046474385574e-01 +6.2248002779995415e-01 +-2.4684932914715350e+00 +-1.4216619962612811e+00 +6.2284308269227162e-01 +-2.4130855822580046e+00 +-1.0265828742457994e+00 +6.1876075476225012e-01 +-2.4229273254354804e+00 +-1.1158147981276774e+00 +6.1682164310153587e-01 +-2.3972909846439046e+00 +-1.1781720688568935e+00 +6.3727965136858800e-01 +-2.3828565674177247e+00 +-9.8872988741969681e-01 +6.6875431114895989e-01 +-2.4286338853478320e+00 +-1.3080931198534167e+00 +6.8299887602817577e-01 +-2.4131769596487014e+00 +-1.3177046399474883e+00 +7.3297327889454866e-01 +-2.4164016019796901e+00 +-1.2159585547309251e+00 +7.2882858733332312e-01 +-2.4061194471976730e+00 +3.2482916640020892e-01 +-3.6302727113821688e-02 +-7.6284209311485507e-01 +8.0762906017848324e-01 +-7.1764305066846376e-02 +-2.9688582447346232e+00 +8.1956787477231252e-01 +-7.0635535270620844e-02 +-2.9793208762913612e+00 +7.6868963062861506e-01 +-6.8035107689269972e-02 +-2.9339251655307423e+00 +8.8988346635534932e-01 +-6.7800676927653805e-02 +-3.0573793145599146e+00 +9.0707429962096509e-01 +1.4159370599702303e-02 +-3.0810347423903082e+00 +-8.9097994877098363e-01 +5.5189670966603585e-02 +-2.4797424213423720e+00 +-1.0067102902165836e+00 +5.9077416450625343e-02 +-2.4093248807574166e+00 +-8.3426953953670957e-01 +6.2834940479542231e-02 +-2.5287241305323040e+00 +-1.0004754415718107e+00 +6.4408551796735367e-02 +-2.4075612511540374e+00 +1.1062680520073336e+00 +8.2339298110601908e-02 +-3.3282031581122160e+00 +7.4217974593746128e-01 +7.6764811251952864e-02 +-2.8977963757284759e+00 +6.0358140105872671e-01 +7.2824134534316007e-02 +-2.7465905854803960e+00 +-8.4677894537519816e-01 +7.8185208725940522e-02 +-2.5261532569702614e+00 +9.5023890119777654e-01 +9.0191144172122803e-02 +-3.1374586974057692e+00 +1.1047133423412030e+00 +9.5953269690461973e-02 +-3.3208344455001737e+00 +-8.7112647821341160e-01 +7.8398577332935968e-02 +-2.5038965296159805e+00 +-9.0408456927571379e-01 +7.9325107456688332e-02 +-2.4789012738954934e+00 +-8.9060556865714657e-01 +7.9991271127674790e-02 +-2.4835083923578809e+00 +-9.3163994705964448e-01 +8.1190007039874779e-02 +-2.4550101383879479e+00 +-9.5242281284861785e-01 +8.1536136478915514e-02 +-2.4461256775812070e+00 +6.1442992562763921e-01 +8.6735368511458591e-02 +-2.7661547195919738e+00 +-1.2038495554137700e+00 +8.9244645025443770e-02 +-2.3727281159394691e+00 +-1.2038495554137700e+00 +8.9244645025443770e-02 +-2.3727281159394691e+00 +8.5191185738104913e-01 +1.0117032081588163e-01 +-2.9975460185833240e+00 +8.3544454326916973e-01 +1.0353490389995786e-01 +-2.9879021188627908e+00 +1.0889822644355793e+00 +1.1993783429984436e-01 +-3.2964896764431928e+00 +8.4940511199498281e-01 +1.0791868614516135e-01 +-3.0056012938046281e+00 +8.5137699198415107e-01 +1.0837871299602045e-01 +-3.0122285316397375e+00 +-1.1294798602854550e+00 +1.0039782910700759e-01 +-2.3762877241707554e+00 +1.3334206072718489e+00 +1.4941993697583619e-01 +-3.6364110503496301e+00 +1.2661625773656271e+00 +1.4498770778771053e-01 +-3.5292135253180228e+00 +3.0807593984367970e-01 +2.8848384103918292e-02 +-7.7161093866002550e-01 +3.1368340515202459e-01 +2.9818051394202114e-02 +-7.7467476157525861e-01 +-1.1282282470895557e+00 +1.1983991534348558e-01 +-2.3766553934723254e+00 +1.1688028417263403e+00 +1.6152824529524978e-01 +-3.4087765639001835e+00 +1.1039075700125018e+00 +1.5824178995411489e-01 +-3.3176376697241601e+00 +1.2855935878084974e+00 +1.7364622398193141e-01 +-3.5766959005559809e+00 +1.8510425352206579e+00 +2.2399925204165599e-01 +-4.5016512168167280e+00 +-1.1410557109202595e+00 +1.2905369877365325e-01 +-2.3784396246113193e+00 +1.8555871094833403e+00 +2.4645725002865368e-01 +-4.5345635000779643e+00 +1.2702982230303410e+00 +1.9427804310931643e-01 +-3.5538971284030807e+00 +-1.1281114366542928e+00 +1.3854842240711757e-01 +-2.3773791161705118e+00 +1.2391971264476720e+00 +2.0790327291598240e-01 +-3.5062234547332469e+00 +-1.1270945931376455e+00 +1.4818633607612955e-01 +-2.3763262998731500e+00 +5.0697112779767872e-01 +1.5770198400415028e-01 +-2.6640851532977456e+00 +1.8021307379962412e+00 +2.8382080163815698e-01 +-4.5556752449298505e+00 +1.2692803769508438e+00 +2.2582582654985814e-01 +-3.5661079099520485e+00 +1.3418880964394919e+00 +1.4972394424259630e-01 +-2.3603236204615476e+00 +1.1125808088232347e+00 +2.1637358488831313e-01 +-3.3385007591693832e+00 +-1.1257124596624257e+00 +1.6298787701205933e-01 +-2.3872298357296873e+00 +1.1967431443513952e+00 +2.2490924285015701e-01 +-3.4420620423512118e+00 +1.2473020967304711e+00 +2.3306295526301549e-01 +-3.5292962708844362e+00 +7.3047708575699277e-01 +1.8862819862426713e-01 +-2.8915480747852502e+00 +7.8162564004326818e-01 +1.9330305032835685e-01 +-2.9272995508044142e+00 +6.8244749210336764e-01 +1.9182320225193941e-01 +-2.8473470266119016e+00 +6.8196763393316084e-01 +1.9161054665932462e-01 +-2.8453279201394985e+00 +-1.4027653911072151e+00 +1.8447308656277392e-01 +-2.4068708321406689e+00 +-1.4349545634004244e+00 +1.8516715167637393e-01 +-2.4114292503260191e+00 +-7.9551811822994045e-01 +1.9295389906368970e-01 +-2.5772772360614717e+00 +-1.1817521922559977e+00 +1.8261017076619432e-01 +-2.3767441737460389e+00 +1.0377825954290167e+00 +2.3664027164727031e-01 +-3.2283976478000111e+00 +-7.4034895411859958e-01 +2.0166838673270171e-01 +-2.6797505149574743e+00 +-7.4034895411859958e-01 +2.0166838673270171e-01 +-2.6797505149574743e+00 +-8.3774474193457638e-01 +1.9233496818695880e-01 +-2.5380765701301073e+00 +6.6178712729094502e-01 +2.0994249891221020e-01 +-2.8292516566382080e+00 +8.5142191077940943e-01 +2.2524399020750704e-01 +-3.0048432660117514e+00 +-1.3063851787106198e+00 +1.9366744022661825e-01 +-2.3947660831387072e+00 +-9.4143044475835858e-01 +1.9615488798744687e-01 +-2.4561497394738594e+00 +9.8388661061583282e-01 +2.4868814931392169e-01 +-3.1848260067291370e+00 +9.8142511828008605e-01 +2.4838774681115638e-01 +-3.1768111886103223e+00 +-8.0071619796971027e-01 +2.0620787587110639e-01 +-2.5750741991376387e+00 +1.3118039014405929e+00 +1.9140324547072227e-01 +-2.4030428357220712e+00 +-8.3937333773901679e-01 +2.0841050152013363e-01 +-2.5422813292091591e+00 +-1.3046179476706916e+00 +2.0140904668377307e-01 +-2.3908091220469334e+00 +-8.0651893995176682e-01 +2.1194203440339507e-01 +-2.5732616980426828e+00 +-1.3870760692822408e+00 +2.0482129648475586e-01 +-2.4031953755563866e+00 +1.0139485463051756e+00 +2.6024955038910752e-01 +-3.2102924541559665e+00 +1.3543383109526974e+00 +1.9052179538326200e-01 +-2.3328605989716853e+00 +6.7765146873885507e-01 +2.3350562386523610e-01 +-2.8379063530139259e+00 +-8.9501479439800580e-01 +2.1223824454920759e-01 +-2.4840260274613075e+00 +-1.0168389411158307e+00 +2.0980408947400636e-01 +-2.4154148879680526e+00 +-1.0510449543986848e+00 +2.1024845417802965e-01 +-2.4091834815753845e+00 +-9.0124404856425366e-01 +2.1727750791911504e-01 +-2.4849727777073505e+00 +-1.1896738343872151e+00 +2.1264294527255431e-01 +-2.3773792963715885e+00 +-9.8769477615696188e-01 +2.1500245803504375e-01 +-2.4276057864165965e+00 +-1.3468063865415274e+00 +2.1993063395609055e-01 +-2.4032525117039514e+00 +9.5742725894182745e-01 +2.7384207810278521e-01 +-3.1423864578315408e+00 +9.5742725894182745e-01 +2.7384207810278521e-01 +-3.1423864578315408e+00 +1.7507259257468908e+00 +3.9775823883694811e-01 +-4.4826665048202985e+00 +7.9144537939041448e-01 +2.5759322360402692e-01 +-2.9309018958721089e+00 +-1.0168303431296921e+00 +2.2028582943932612e-01 +-2.4181797642194205e+00 +-1.1707710559755011e+00 +2.1913017005197205e-01 +-2.3864632450390091e+00 +7.8311865745903164e-01 +2.5916012258005844e-01 +-2.9287536780222299e+00 +6.1725000030455501e-01 +2.4433065945680227e-01 +-2.7735041589707947e+00 +-1.2488056123588476e+00 +2.2045403425798274e-01 +-2.3684746133156276e+00 +-1.3836719867983116e+00 +2.2664908069724823e-01 +-2.4076983728006423e+00 +-1.1089181906237568e+00 +2.2178475578050952e-01 +-2.3893461131734841e+00 +-1.1146924770699931e+00 +2.2234619816377790e-01 +-2.3837771799395893e+00 +-1.3141683342458346e+00 +2.2640683832610309e-01 +-2.3974284819875424e+00 +-1.1277204806835002e+00 +2.2428013366271540e-01 +-2.3849781621589381e+00 +5.3383698646251010e-01 +2.4949055578667623e-01 +-2.6966172210714991e+00 +5.3440714670489253e-01 +2.4963629927489109e-01 +-2.6981021160121319e+00 +-1.1219391717473839e+00 +2.3944358672037994e-01 +-2.3836271574771910e+00 +-1.3179666320883989e+00 +2.4697918134997762e-01 +-2.4003684495269617e+00 +6.8558836543774682e-01 +2.8024935914577165e-01 +-2.8373989455262345e+00 +-7.8053274761984381e-01 +2.6713641654169501e-01 +-2.6100267787402620e+00 +-1.1223022412180148e+00 +2.4923526150462966e-01 +-2.3848441464405790e+00 +-1.3285521841110666e+00 +2.5735068849001191e-01 +-2.4002182532807002e+00 +-1.3285521841110666e+00 +2.5735068849001191e-01 +-2.4002182532807002e+00 +-7.7899220104730527e-01 +2.7308364071598989e-01 +-2.6144058507741930e+00 +-7.6682985788116953e-01 +2.7670412462818522e-01 +-2.6364138339024645e+00 +6.0924861151080345e-01 +2.9117953647442063e-01 +-2.7642562727091406e+00 +-1.2498376551870849e+00 +2.6364463474846989e-01 +-2.3715286223973409e+00 +-1.3135047570002403e+00 +2.6741773008401148e-01 +-2.3954214525338222e+00 +-1.1271804481115146e+00 +2.6496924901525759e-01 +-2.3804819457013844e+00 +-1.1271804481115146e+00 +2.6496924901525759e-01 +-2.3804819457013844e+00 +5.9368699708603867e-01 +2.9230160442896930e-01 +-2.7291149327028128e+00 +1.3438124526789710e+00 +2.6033604454195042e-01 +-2.3545049326197183e+00 +-1.1209613787807871e+00 +2.7035516634573509e-01 +-2.3834362719764530e+00 +5.5884014344761890e-01 +2.9714441971991251e-01 +-2.6998768574646603e+00 +5.5884014344761890e-01 +2.9714441971991251e-01 +-2.6998768574646603e+00 +-1.3165654952496928e+00 +2.7824147622044004e-01 +-2.3992869615122383e+00 +-1.3287288421975374e+00 +2.7826312111194584e-01 +-2.4002567257319503e+00 +-9.5195518193363693e-01 +2.8653728522869343e-01 +-2.4518615164725199e+00 +-9.5195518193363693e-01 +2.8653728522869343e-01 +-2.4518615164725199e+00 +1.3386040545012099e+00 +2.7577751621730873e-01 +-2.3568467814276364e+00 +9.3138719204034792e-01 +3.6121537705334539e-01 +-3.1165737511807361e+00 +-1.1029355832442675e+00 +2.9141410515910915e-01 +-2.3965044016508061e+00 +-7.9782362681111396e-01 +3.1280655097451582e-01 +-2.5804436962456259e+00 +1.3791148375120614e+00 +2.8492513671056735e-01 +-2.3545644378012525e+00 +1.3177253063803229e+00 +2.9672177844939052e-01 +-2.4349054937568693e+00 +-8.9375557982737841e-01 +3.1800722284921096e-01 +-2.4857930367756276e+00 +-8.9362779310415275e-01 +3.1719709088656128e-01 +-2.4851252864798048e+00 +-9.3818196653529162e-01 +3.1430484562871330e-01 +-2.4550986437935483e+00 +-9.0316093750736803e-01 +3.1816268381182344e-01 +-2.4850619582683002e+00 +-1.3853356420702074e+00 +3.2215194398953362e-01 +-2.4024226253858982e+00 +-1.3859208094083622e+00 +3.2222674451220923e-01 +-2.4032557281176761e+00 +-1.0594525897688281e+00 +3.1762474037053035e-01 +-2.3994795048395940e+00 +-1.2963280419559344e+00 +3.2064271481177470e-01 +-2.3957585485001545e+00 +5.5725174874031991e-01 +3.4981552856396370e-01 +-2.7198561798834398e+00 +-1.0088738030783380e+00 +3.2166339662942156e-01 +-2.4214280966602217e+00 +-1.0080984010510436e+00 +3.2133937438795607e-01 +-2.4194996711623413e+00 +-1.1560359081953995e+00 +3.1966245356383105e-01 +-2.3843946640067086e+00 +-1.0032888251475691e+00 +3.2645332165106683e-01 +-2.4202395908324177e+00 +4.3251297134926331e-01 +3.4796122023473186e-01 +-2.6586843292400282e+00 +-1.1599886351915150e+00 +3.3088625897615126e-01 +-2.3915547577219942e+00 +-7.3159267779428450e-01 +3.7385640807718851e-01 +-2.6950036132729007e+00 +-1.1214682977673307e+00 +3.4093419582887635e-01 +-2.3873702274836437e+00 +6.0895541931197772e-01 +3.8645847926757176e-01 +-2.7596216503949735e+00 +-1.1213330975731428e+00 +3.5160684139162945e-01 +-2.3870007714555554e+00 +1.5161404093718223e+00 +3.7504544751758062e-01 +-2.5537450158883890e+00 +5.2830820096304132e-01 +3.8466014736790516e-01 +-2.6806844702464532e+00 +6.0525000792252703e-01 +3.9884153924768245e-01 +-2.7599850838685880e+00 +5.0507000719440498e-01 +3.9351688422387754e-01 +-2.6755526847411626e+00 +-1.1225185194947251e+00 +3.6454071002467958e-01 +-2.3907455581799297e+00 +5.5546185171523743e-01 +4.0153745325946855e-01 +-2.7165598038141674e+00 +4.6225892493568133e-01 +3.9289277152598834e-01 +-2.6596010820231517e+00 +4.2091077314329689e-01 +3.9923319669113211e-01 +-2.6596135837803150e+00 +5.2251745259500482e-01 +4.0581610381110844e-01 +-2.6878159592314428e+00 +-7.3604073196515696e-01 +4.1867763305244871e-01 +-2.6897232939761486e+00 +4.8366725530960403e-01 +4.0914254931670690e-01 +-2.6684316906037462e+00 +4.6544176522024538e-01 +4.1234741091068478e-01 +-2.6590830685835942e+00 +-1.1201264181836832e+00 +3.8726901570779820e-01 +-2.3892389155819851e+00 +-7.8037610140972258e-01 +4.1668165479995489e-01 +-2.6047459741782482e+00 +-7.9979021867471745e-01 +4.1817933657043310e-01 +-2.5815590102139319e+00 +-8.0040427308959650e-01 +4.1869575617343963e-01 +-2.5837064533571095e+00 +-8.0442338878861352e-01 +4.2481730606900686e-01 +-2.5781061386053654e+00 +5.0775983105564604e-01 +4.3873551222807844e-01 +-2.6861049806535373e+00 +4.5848619793911405e-01 +4.3869441997939684e-01 +-2.6701855435861050e+00 +-8.9413736227149432e-01 +4.2346902381105334e-01 +-2.4911988032866677e+00 +-6.9847695536027754e-01 +4.7626183360026558e-01 +-2.8124216265436006e+00 +-1.0130686191514910e+00 +4.2247919053561139e-01 +-2.4241569910723575e+00 +-9.4528090139316423e-01 +4.3033822978202257e-01 +-2.4603836393600385e+00 +-1.3761681442217448e+00 +4.3821515478297246e-01 +-2.4083531660036157e+00 +-1.0549309502301969e+00 +4.3404902117851801e-01 +-2.4120830932013564e+00 +-1.0661361566616050e+00 +4.3474526763784177e-01 +-2.4099115224625152e+00 +-1.3120815667447170e+00 +4.3786380933033303e-01 +-2.3986193568421807e+00 +-7.1825424685884975e-01 +4.9854441749078515e-01 +-2.7218567887256575e+00 +-8.7478492613665815e-01 +4.6397591063700561e-01 +-2.5070148851517366e+00 +-1.1197125644745698e+00 +4.5032676716732722e-01 +-2.3909075060670562e+00 +-9.0692778058694379e-01 +4.6566237807812133e-01 +-2.4917212324660425e+00 +-9.0692778058694379e-01 +4.6566237807812133e-01 +-2.4917212324660425e+00 +-1.1184084126729581e+00 +4.6772808423520318e-01 +-2.3908156572014523e+00 +-7.7945174569908393e-01 +5.0358522561878161e-01 +-2.6012116838559405e+00 +-9.6269876219149098e-01 +4.8206732668107583e-01 +-2.4538388704147294e+00 +-1.3505460559636713e+00 +4.9979642778000216e-01 +-2.4060296127339824e+00 +-1.3505460559636713e+00 +4.9979642778000216e-01 +-2.4060296127339824e+00 +-1.3318430089739735e+00 +4.9937089010032421e-01 +-2.4022703399142107e+00 +-8.7014889789019012e-01 +5.2757859525676398e-01 +-2.4875505282109796e+00 +-7.2966360389970120e-01 +5.9843640606517179e-01 +-2.7044297117448668e+00 +-7.3337717389192225e-01 +6.0396326514546805e-01 +-2.6984645281828858e+00 +-7.5727883228019388e-01 +6.0531173555528672e-01 +-2.6475559032888292e+00 +-1.0440611777966449e+00 +5.5691842745366871e-01 +-2.4118273877270289e+00 +-9.8728897940815108e-01 +5.6388220381723053e-01 +-2.4317267998968539e+00 +-1.2893779286279650e+00 +5.6363503251125335e-01 +-2.3970701121121891e+00 +-7.3305037168876586e-01 +6.4165860166769173e-01 +-2.7056671915614032e+00 +-7.3347376053103219e-01 +6.4140890272674855e-01 +-2.7071596225150634e+00 +-8.8983061471944425e-01 +6.0818841220243225e-01 +-2.4959165677555859e+00 +-8.1427769634408054e-01 +6.4341632945897853e-01 +-2.5819961340851925e+00 +-9.8107880748568521e-01 +6.1123094639595099e-01 +-2.4349282239183001e+00 +-7.9743188786745978e-01 +6.4709815230041068e-01 +-2.5906106683987078e+00 +-1.0028314641838401e+00 +6.1117026304607802e-01 +-2.4220741037093219e+00 +-8.8595037561998835e-01 +6.6060124695072209e-01 +-2.5000448450720425e+00 +-1.0505453999853342e+00 +6.4884853089737826e-01 +-2.4199861410360599e+00 +-1.0504329455051959e+00 +6.4906925396212722e-01 +-2.4204802546660771e+00 +-1.2684295325807826e+00 +7.1681910368111990e-01 +-2.4084289657660678e+00 +-1.1885655844175158e+00 +7.1470742851133096e-01 +-2.3995541255932822e+00 +-1.3058577452202085e+00 +7.3445475672665528e-01 +-2.4205706579400630e+00 +-1.2599602035720774e+00 +7.3273763490053179e-01 +-2.4059131503687761e+00 +-1.1835048142923295e+00 +7.3165540351495106e-01 +-2.4005004495045821e+00 +-1.2635243514688030e+00 +7.3693009125104514e-01 +-2.4049481215216013e+00 +-1.2635243514688030e+00 +7.3693009125104514e-01 +-2.4049481215216013e+00 +-1.2133597014694151e+00 +7.4035950900120617e-01 +-2.3957262486642952e+00 +-1.2133597014694151e+00 +7.4035950900120617e-01 +-2.3957262486642952e+00 +-1.1941537230763308e+00 +7.4614134806439847e-01 +-2.3919644266449276e+00 +-1.1534733826071994e+00 +7.5126635952954457e-01 +-2.3903448898201107e+00 +-1.1308394514412154e+00 +9.0771148856473827e-01 +-2.6502936950132274e+00 +7.9487566288268696e-01 +-7.4954747438237976e-02 +-2.9540279788253354e+00 +8.0060668867156615e-01 +-6.1086275936066567e-02 +-2.9546390963582612e+00 +8.3025257675198649e-01 +1.8921991283399525e-02 +-2.9875716525866398e+00 +9.2955511324927576e-01 +3.6146534515774438e-02 +-3.1028432921199438e+00 +8.3635950166502449e-01 +5.3007995926616175e-02 +-2.9925157494914245e+00 +-8.4195489288896519e-01 +5.9151500246315228e-02 +-2.5251085926554162e+00 +6.7885702346698140e-01 +6.3041763599309325e-02 +-2.8560871283710094e+00 +-8.4645666927926033e-01 +6.2557556113756782e-02 +-2.5262751473840508e+00 +-1.1777615983098686e+00 +6.7674045240660008e-02 +-2.3747844251131820e+00 +1.0833942900565170e+00 +8.7393900173516503e-02 +-3.2933591749957656e+00 +6.1297938850629963e-01 +7.6075288573282801e-02 +-2.7627102645146913e+00 +5.6573142413753486e-01 +7.4877217923095388e-02 +-2.7161521916773093e+00 +9.7975813226450936e-01 +9.1598773014298862e-02 +-3.1874917067326121e+00 +1.0769022237158021e+00 +9.5379674881074641e-02 +-3.2831597974089561e+00 +6.0905714860285254e-01 +7.9900256473687217e-02 +-2.7677605866458355e+00 +1.5495966618741681e+00 +1.1693532656604690e-01 +-3.9527477480086031e+00 +9.7206095414724658e-01 +9.5732881528028474e-02 +-3.1779876278076142e+00 +-8.9739165221435546e-01 +8.0559889270629889e-02 +-2.4808388983199681e+00 +1.0523555422371269e+00 +9.9815933277128371e-02 +-3.2427121340790115e+00 +9.1798453796339408e-01 +9.8548330086474997e-02 +-3.1068644545175021e+00 +7.2741035591769543e-01 +9.5215366878899005e-02 +-2.8971528781852274e+00 +9.4801588416605020e-01 +1.0597653605635193e-01 +-3.1421697219655012e+00 +1.3367532006442016e+00 +1.2652787531211229e-01 +-3.6450548863949654e+00 +1.2676651092589284e+00 +1.3096510234917735e-01 +-3.5502651076625531e+00 +7.7659244799924487e-01 +1.0892107221240804e-01 +-2.9433822974800106e+00 +1.1600348579874866e+00 +1.2820533341292586e-01 +-3.4082269823842477e+00 +8.6037268326170535e-01 +1.1271616311750358e-01 +-3.0261815963132026e+00 +5.4342899719285953e-01 +1.0670739395647161e-01 +-2.6891055415897438e+00 +1.1742765657155914e+00 +1.3725619070934345e-01 +-3.4189240885283128e+00 +1.0285847296648851e+00 +1.3072134013125178e-01 +-3.2116697859711567e+00 +8.2657880192598876e-01 +1.2527704088203664e-01 +-2.9750632955818430e+00 +-1.2685836879897312e+00 +1.1131367144148364e-01 +-2.3849724317033205e+00 +1.2454530355680364e+00 +1.5723132968814865e-01 +-3.5204847538631605e+00 +6.4283989347090686e-01 +1.2941928755054169e-01 +-2.7998214890748132e+00 +5.4916852720572029e-01 +1.2820873084451781e-01 +-2.7049993599336748e+00 +9.2247799557024113e-01 +1.5127192303180004e-01 +-3.1034371442528159e+00 +1.2604146195567458e+00 +1.7428079609148941e-01 +-3.5441348932688417e+00 +-1.1260479374543915e+00 +1.2500849909934969e-01 +-2.3856957637130587e+00 +1.1226536776131431e+00 +1.6497328521849469e-01 +-3.3455171935999979e+00 +1.2622054767354383e+00 +1.8539801044838206e-01 +-3.5495999637432605e+00 +1.1691366629020044e+00 +1.8031827040128137e-01 +-3.4179404527600492e+00 +1.1698947498301608e+00 +1.9196983166094803e-01 +-3.4211393596734219e+00 +8.5270370363647030e-01 +1.7015766804489382e-01 +-3.0107674538545850e+00 +1.0284115521007990e+00 +1.8946314742353271e-01 +-3.2221663315714077e+00 +5.8861673115062141e-01 +1.6137079153997014e-01 +-2.7472821716284361e+00 +5.8861673115062141e-01 +1.6137079153997014e-01 +-2.7472821716284361e+00 +1.2807041501819987e+00 +2.1438876664084455e-01 +-3.5728837048069488e+00 +9.7733143588170368e-01 +1.8916173850819870e-01 +-3.1638357821028418e+00 +1.3218249492336009e+00 +1.4774519568091107e-01 +-2.4518763964816821e+00 +1.0477695420375124e+00 +1.9763358868805833e-01 +-3.2352625518026357e+00 +1.1091941728231141e+00 +2.0654318461017382e-01 +-3.3204229812212525e+00 +8.3527229873983500e-01 +1.8498681739308159e-01 +-2.9847088227655858e+00 +1.0134720924346494e+00 +2.0385864660472283e-01 +-3.2171802036914956e+00 +7.1875428551258869e-01 +1.8261381262753709e-01 +-2.8806990433558077e+00 +1.0013594235035201e+00 +2.0730542763928089e-01 +-3.1979328537048639e+00 +1.0013594235035201e+00 +2.0730542763928089e-01 +-3.1979328537048639e+00 +5.5792069848136971e-01 +1.7561730629586284e-01 +-2.7155362637676501e+00 +1.1764354215047683e+00 +2.2641659495073729e-01 +-3.4278755913345020e+00 +6.8736538203726238e-01 +1.8579115744680610e-01 +-2.8283404101933090e+00 +6.7056556175056359e-01 +1.8555002309449500e-01 +-2.8342162672497344e+00 +-1.3162243881558013e+00 +1.6855990586199049e-01 +-2.3947457330636248e+00 +-1.3162243881558013e+00 +1.6855990586199049e-01 +-2.3947457330636248e+00 +-1.1410612474703834e+00 +1.6660937525973735e-01 +-2.3803645191785874e+00 +1.3180255443596582e+00 +1.6197924925037610e-01 +-2.4270757879611682e+00 +-7.3336945523077668e-01 +1.8451020541573213e-01 +-2.6868681550441127e+00 +-7.9177491873861428e-01 +1.8701476862305919e-01 +-2.5683749055676821e+00 +-1.0072774139079652e+00 +1.7946569566381987e-01 +-2.4173743148069966e+00 +-7.8519883111659461e-01 +1.7845430345678043e-01 +-2.3534094600085247e+00 +-7.3929570561588376e-01 +2.0722449976478219e-01 +-2.6879865794159707e+00 +9.8166401936487613e-01 +2.4013847319394258e-01 +-3.1730438214178869e+00 +1.0497643668386487e+00 +2.4891886971154714e-01 +-3.2477279374132149e+00 +7.6971855998782202e-01 +2.2656490115861799e-01 +-2.9176733383377016e+00 +-9.3562525623641901e-01 +1.9815139094459297e-01 +-2.4604909338992207e+00 +-1.2190798897242590e+00 +1.9441659013561818e-01 +-2.3654362683126782e+00 +7.5778517683949465e-01 +2.2765899539846307e-01 +-2.9083610595231324e+00 +1.0749065667600659e+00 +2.5737111556983372e-01 +-3.2641008219278209e+00 +9.9188294666681898e-01 +2.5399398930622380e-01 +-3.1872695117319263e+00 +8.9473369369731670e-01 +2.4605278049286439e-01 +-3.0708834588910929e+00 +-9.2171845806610708e-01 +2.0569385276166050e-01 +-2.4764258489406172e+00 +8.7757851593576319e-01 +2.4637461292457530e-01 +-3.0465724970079857e+00 +8.6236278105880282e-01 +2.4330216100536856e-01 +-3.0174151520035704e+00 +-1.0689629451887657e+00 +2.0254256506753263e-01 +-2.3973578339953407e+00 +-1.2083712406715241e+00 +2.0133502036735718e-01 +-2.3562972730888516e+00 +-1.3795946575102747e+00 +2.0706741255979574e-01 +-2.4009628952904043e+00 +1.0175944593949757e+00 +2.6791971596034103e-01 +-3.2130392470388562e+00 +1.3060901562127951e+00 +3.0344874353617951e-01 +-3.6142039128991690e+00 +1.2982893759476082e+00 +3.0156636144540250e-01 +-3.5916032497672217e+00 +6.5992394601431781e-01 +2.3267908607309398e-01 +-2.8121912131421576e+00 +8.3821243749869689e-01 +2.5017571861100552e-01 +-2.9943097444817872e+00 +-1.0392189371996432e+00 +2.0930672038296502e-01 +-2.4121565234939393e+00 +-1.4129808365077414e+00 +2.1502520543642917e-01 +-2.4107888915103097e+00 +-1.2378363575029883e+00 +2.1160303913028705e-01 +-2.3668585519487380e+00 +9.6387048369375883e-01 +2.7354073423897174e-01 +-3.1412884262064584e+00 +9.6603501266830938e-01 +2.8202014517453328e-01 +-3.1529628992933940e+00 +5.7092025104932409e-01 +2.4265110633941461e-01 +-2.7199762757855632e+00 +8.4623938653709252e-01 +2.7082688439245661e-01 +-2.9851989550815277e+00 +7.0902401855838137e-01 +2.6294406846661844e-01 +-2.8675123821472472e+00 +1.8417527372390317e+00 +4.5047939350424365e-01 +-4.6332391143253222e+00 +9.2789976486921921e-01 +2.9637235416706847e-01 +-3.0964087665849993e+00 +5.9317942060847961e-01 +2.6201436630728886e-01 +-2.7431132492468984e+00 +8.3286601544017769e-01 +2.9350655957278649e-01 +-2.9632163352808010e+00 +5.4769723816599047e-01 +2.6636436703698402e-01 +-2.7043983458887570e+00 +5.3041062766909863e-01 +2.6713262852944741e-01 +-2.6808638904955178e+00 +5.3108542497735212e-01 +2.6770729367117946e-01 +-2.6850075641839317e+00 +1.3611679342530063e+00 +2.6397766928884508e-01 +-2.5907317737903028e+00 +9.3862747063788332e-01 +3.1669255314232836e-01 +-3.1127233954654843e+00 +9.4141965854535303e-01 +3.1669741386661676e-01 +-3.1220930066867503e+00 +9.4172681684141790e-01 +3.1669069334707689e-01 +-3.1225136606084010e+00 +4.5507147185030722e-01 +2.6903415703287187e-01 +-2.6588092595297015e+00 +-7.5189548486383995e-01 +2.7620724643470579e-01 +-2.6571571010913999e+00 +5.3671153993278198e-01 +2.7607599402886168e-01 +-2.6934811267763186e+00 +1.3312170760892681e+00 +2.5076318836881017e-01 +-2.3812105648567798e+00 +5.9492536951153108e-01 +2.9350656783564449e-01 +-2.7581289883618312e+00 +5.9250552857310790e-01 +2.9161015853092453e-01 +-2.7446117574737241e+00 +-7.6230378106574737e-01 +2.9916433214937954e-01 +-2.6395087285844263e+00 +5.0533595536678588e-01 +2.9633841866932037e-01 +-2.6720995158427585e+00 +-7.3895579924207233e-01 +3.0819715550134841e-01 +-2.6870553778271353e+00 +-7.3859408795260861e-01 +3.0864555527763177e-01 +-2.6858964454087344e+00 +-7.5604269507767918e-01 +3.0463226046541636e-01 +-2.6452745350525557e+00 +-7.6474591402236791e-01 +3.0927830987689109e-01 +-2.6356918084197640e+00 +-1.1838594150236965e+00 +2.8760010988643625e-01 +-2.3781858451134772e+00 +-1.1945135578337893e+00 +2.8825498170717367e-01 +-2.3758428488595866e+00 +1.0372843150884958e+00 +3.9610548192595563e-01 +-3.3451431881907023e+00 +1.3671183603837413e+00 +2.7598399869674783e-01 +-2.3084660483924635e+00 +1.3984621924980185e+00 +2.7739720051792677e-01 +-2.2980689728756838e+00 +8.6652559639228666e-01 +3.9070662185561178e-01 +-3.1706614970972242e+00 +5.5044460318904087e-01 +3.3271302356932414e-01 +-2.7045982387901386e+00 +6.1490945583404710e-01 +3.4628399499700191e-01 +-2.7744955294884024e+00 +-1.3777483940397230e+00 +3.1598258573300136e-01 +-2.4041130758537879e+00 +-1.0589489073295415e+00 +3.1311836174388674e-01 +-2.4151216502175057e+00 +1.3337015107218240e+00 +3.0083083085962908e-01 +-2.3550453959861386e+00 +-7.3263048580395906e-01 +3.4663982667639731e-01 +-2.6971279379105715e+00 +-1.3582736410313110e+00 +3.2013561668662066e-01 +-2.4060328101665296e+00 +6.1874942232912356e-01 +3.5527451192326387e-01 +-2.7711556322609279e+00 +6.1874942232912356e-01 +3.5527451192326387e-01 +-2.7711556322609279e+00 +-1.3154368244469778e+00 +3.2125054787961294e-01 +-2.3999133514913367e+00 +-1.0181794204202101e+00 +3.2100277021842955e-01 +-2.4185249302346219e+00 +-1.0559581395215063e+00 +3.2159275276092963e-01 +-2.4039721850429188e+00 +5.4367568533928667e-01 +3.5270468320552811e-01 +-2.7009797496093606e+00 +5.5116571850859541e-01 +3.5457671691282122e-01 +-2.7082661978072706e+00 +-1.1691504752901027e+00 +3.2510155964998705e-01 +-2.3861521458425110e+00 +-1.2949745257307979e+00 +3.3054128684498385e-01 +-2.4004755216453653e+00 +-1.1601582476615750e+00 +3.3704935808484504e-01 +-2.3917541416503956e+00 +5.6947190426502747e-01 +3.8070156575040848e-01 +-2.7216985851844546e+00 +6.2542486191779811e-01 +4.2075416181167691e-01 +-2.7854623875182423e+00 +4.5366518307114950e-01 +4.0332210076207803e-01 +-2.6466674238410008e+00 +4.3717961670529865e-01 +4.0385644745831834e-01 +-2.6455661927741607e+00 +4.3281915777778451e-01 +4.1020555152404392e-01 +-2.6536603321575214e+00 +4.3188968095677299e-01 +4.0879676601983861e-01 +-2.6453987949793643e+00 +-7.9320525188588986e-01 +4.1509486032062637e-01 +-2.5831231418995486e+00 +6.2763775622235651e-01 +4.5588325615120184e-01 +-2.8166239679485572e+00 +-9.7500533542975854e-01 +4.0431276892433415e-01 +-2.4273066079938319e+00 +-1.0115169614946427e+00 +4.0548006762730321e-01 +-2.4121571392482681e+00 +4.9019088529302968e-01 +4.3885433509615096e-01 +-2.6689807487415762e+00 +1.8341689485608967e+00 +5.4272927276257332e-01 +-3.0939984439586437e+00 +-9.8346401800517869e-01 +4.2668349660698973e-01 +-2.4324743089786827e+00 +-1.0091402071192250e+00 +4.2763651474421510e-01 +-2.4229024075435923e+00 +-1.3880437544628896e+00 +4.3366349134267690e-01 +-2.4111289895887809e+00 +-7.9181185461231729e-01 +4.5986878762996997e-01 +-2.5940034707498292e+00 +-1.1135263673528562e+00 +4.2984652886791302e-01 +-2.3877200611739768e+00 +-7.3478948868199001e-01 +4.8073788177461957e-01 +-2.6856595273126778e+00 +-1.3086723367734165e+00 +4.4317671092374117e-01 +-2.4025109994587543e+00 +5.4177561335202751e-01 +5.1307716491956690e-01 +-2.8423574532122351e+00 +-1.1361906980018033e+00 +4.4576242239703656e-01 +-2.3912721937707229e+00 +-9.8746471890431942e-01 +4.7195467442693229e-01 +-2.4311401973188160e+00 +-9.7148749886255492e-01 +4.9280053476923036e-01 +-2.4355288643594775e+00 +-9.7227383308304038e-01 +4.9297744983234332e-01 +-2.4368384243532577e+00 +-1.0160754249157868e+00 +4.9481228017192747e-01 +-2.4188011549961517e+00 +-1.1142559724055221e+00 +4.9778951877418093e-01 +-2.3868237086075839e+00 +-9.8311829487151436e-01 +5.1185394604566881e-01 +-2.4296531528489664e+00 +-1.1159540033137423e+00 +5.1455439645842416e-01 +-2.3812466857101198e+00 +-7.2440911939050878e-01 +5.9391021573902314e-01 +-2.7024242412995143e+00 +-1.3390769412561905e+00 +5.8296922612866642e-01 +-2.4129086554573869e+00 +-8.6870087928353756e-01 +6.0656707248263286e-01 +-2.5100816354087945e+00 +-7.9219510866350362e-01 +6.2424286633410442e-01 +-2.5766644468380613e+00 +-1.2179321933955054e+00 +5.9639119230404225e-01 +-2.3993576858278831e+00 +-1.1707981156083156e+00 +5.9610742938949646e-01 +-2.3966416311594663e+00 +-1.2251450691381185e+00 +6.0300670837678005e-01 +-2.3959332260832320e+00 +-1.2647300598742963e+00 +6.0452821492221953e-01 +-2.4016324307811439e+00 +-1.3134246830843652e+00 +6.1271538942916726e-01 +-2.4025220401185838e+00 +-1.4366561723156590e+00 +6.2361092356516135e-01 +-2.4161803999438241e+00 +-8.7648778985746778e-01 +6.4362095215298809e-01 +-2.5111506110270008e+00 +-1.4038455774062881e+00 +6.3827950939213129e-01 +-2.4043033530761750e+00 +-1.3354617726946898e+00 +6.5327420320985097e-01 +-2.4148661107346743e+00 +-1.2525622715960261e+00 +6.5547602214808431e-01 +-2.4098400906222102e+00 +-1.1264845742129537e+00 +7.1021997745471865e-01 +-2.3962526622074205e+00 +-1.2460048137245932e+00 +7.3436810100574601e-01 +-2.3958291377001726e+00 +-1.2251456565786707e+00 +7.3506456857117852e-01 +-2.3975177204719844e+00 +-9.5325547699628921e-01 +8.0307767125013063e-01 +-2.6009515689309901e+00 +-1.1749821164955541e+00 +7.4685008244510664e-01 +-2.3931462165719068e+00 +-1.1284886944547659e+00 +8.1326799455780086e-01 +-2.5418138019261427e+00 +7.9600893107189186e-01 +-7.5969918705770925e-02 +-2.9294122177655555e+00 +8.9041546184471465e-01 +-4.6028264696397994e-02 +-3.0770659282051187e+00 +8.4128881269660061e-01 +-3.0384158300610767e-02 +-3.0273935289458089e+00 +9.2553549506822286e-01 +3.1849864205920113e-02 +-3.1094824043374145e+00 +9.4578184718455627e-01 +4.8974527041496740e-02 +-3.1447171910372376e+00 +8.2397754693853609e-01 +5.3558993816069614e-02 +-2.9830555900213089e+00 +9.9908671304212371e-01 +6.2459401089177434e-02 +-3.2104490352553396e+00 +9.4924712224779673e-01 +6.5013414241197207e-02 +-3.1552126261353850e+00 +1.0014565086227059e+00 +7.4063770124438807e-02 +-3.2177508528669518e+00 +-9.7828696184074337e-01 +6.6426972263500986e-02 +-2.4369630301714613e+00 +-1.0742499610104725e+00 +6.8905077791448388e-02 +-2.3894472048825719e+00 +7.9731179451768774e-01 +8.5574687844211642e-02 +-2.9392297717867413e+00 +5.5285649973666673e-01 +8.1345306900255834e-02 +-2.7057232538536202e+00 +4.8391224252347548e-01 +8.1668705008001025e-02 +-2.6696482759384019e+00 +7.7016991215699815e-01 +9.2249411080941535e-02 +-2.9402909675130577e+00 +-8.9318342824440700e-01 +8.5752209029788695e-02 +-2.4790758464859994e+00 +7.9755809552357548e-01 +1.0025216814624842e-01 +-2.9455407354048391e+00 +1.2732951153353884e+00 +1.2546786354896730e-01 +-3.5523596085482261e+00 +1.3458940089615121e+00 +1.3180554989177312e-01 +-3.6555269199990721e+00 +1.3286228100348161e+00 +1.3203957680990011e-01 +-3.6445263916034851e+00 +1.1826638072875209e+00 +1.3246649847929898e-01 +-3.4319041374092580e+00 +8.1711555299966188e-01 +1.1330432692907466e-01 +-2.9603419101173842e+00 +7.8370522470609194e-01 +1.1298323090946698e-01 +-2.9282396318881991e+00 +1.3860242472733484e+00 +1.0305730626557449e-01 +-2.5950071494758475e+00 +1.1530345804719888e+00 +1.3888298187957063e-01 +-3.3970259860874386e+00 +1.4933930236883695e+00 +1.6109240264275748e-01 +-3.9169184616927217e+00 +1.1297168941606617e+00 +1.4039432824703371e-01 +-3.3638881129005545e+00 +9.8232360332045920e-01 +1.3986465284174524e-01 +-3.1760126800246082e+00 +1.3484104454683179e+00 +1.6574299906965706e-01 +-3.6710667186700197e+00 +1.3322524743249711e+00 +1.6856577191170949e-01 +-3.6408911344709747e+00 +9.5052473112948777e-01 +1.4524042006075341e-01 +-3.1333632562746381e+00 +1.3095894433148394e+00 +1.7049053710967194e-01 +-3.6235312407505722e+00 +1.0795592755150287e+00 +1.5605842096382860e-01 +-3.2859798257571047e+00 +5.9822161664410811e-01 +1.3800810401796398e-01 +-2.7475553458696917e+00 +1.1594616247428395e+00 +1.7507539465014932e-01 +-3.4067466621571056e+00 +1.0639512216799918e+00 +1.7193004981266907e-01 +-3.2641363994823189e+00 +1.2877731858321166e+00 +1.9463066711478652e-01 +-3.5792638790044862e+00 +9.8793215352536445e-01 +1.7610506263354092e-01 +-3.1812850506113972e+00 +1.0219316270550847e+00 +1.7926136612274463e-01 +-3.2136761105725200e+00 +1.1903806236193359e+00 +1.9388160374668834e-01 +-3.4483010083072760e+00 +1.0286118238468283e+00 +1.8488736628494346e-01 +-3.2306140249948907e+00 +1.0092154165486746e+00 +1.8372058369118757e-01 +-3.2046020577262921e+00 +1.1886360546006109e+00 +2.0029007957240219e-01 +-3.4324445165848494e+00 +1.0202844421820918e+00 +1.9183921915651186e-01 +-3.2210759021518927e+00 +1.0190164428089006e+00 +1.9154928235316088e-01 +-3.2169395384828419e+00 +1.1074013807808676e+00 +1.9856049353600733e-01 +-3.3274313523455845e+00 +7.1792740910200514e-01 +1.7119023506476205e-01 +-2.8762280230705315e+00 +1.2038052510137593e+00 +2.1532425018438467e-01 +-3.4605891441740444e+00 +1.0180033525394028e+00 +2.0248247964441476e-01 +-3.2149634652408445e+00 +7.1789245884711528e-01 +1.8254565562991315e-01 +-2.8768825573595440e+00 +1.8599977087622517e+00 +2.8554049785273289e-01 +-4.4070071977224456e+00 +1.3338124041866337e+00 +1.5387746188657506e-01 +-2.3495471259905218e+00 +1.2222075587569696e+00 +2.3090875347650083e-01 +-3.4837415020306302e+00 +1.3191461026596361e+00 +1.5887050640411352e-01 +-2.3928048509857711e+00 +1.3303245147009835e+00 +1.6072635838559296e-01 +-2.3658840212834953e+00 +1.3370094817636031e+00 +1.6395272866957405e-01 +-2.3532983281285458e+00 +1.0658231527462869e+00 +2.3672357011791834e-01 +-3.2690737623476731e+00 +1.3619268507050362e+00 +1.9077393564099099e-01 +-2.6069064563048969e+00 +1.3619268507050362e+00 +1.9077393564099099e-01 +-2.6069064563048969e+00 +1.2337813635708648e+00 +2.6165974362587768e-01 +-3.5060486364665548e+00 +9.9816960606473970e-01 +2.3983864622681234e-01 +-3.1959082783797528e+00 +9.9816960606473970e-01 +2.3983864622681234e-01 +-3.1959082783797528e+00 +1.1478121973409607e+00 +2.5671409200907486e-01 +-3.3842982823986429e+00 +1.1465298277878564e+00 +2.5607903392587239e-01 +-3.3800403856789307e+00 +-8.6296012698853686e-01 +2.0058998051967694e-01 +-2.5172702491157186e+00 +5.5840606821026539e-01 +2.1006501877762751e-01 +-2.7129722372741423e+00 +1.0478739751694639e+00 +2.5431738490132566e-01 +-3.2331231442868558e+00 +1.0490611582105800e+00 +2.5703209888942957e-01 +-3.2240833347563265e+00 +1.2424466650056543e+00 +2.8769135561955816e-01 +-3.5260111476966762e+00 +-1.0219087591421110e+00 +2.0492843605624980e-01 +-2.4144729191264505e+00 +9.5488682464173069e-01 +2.5770096182139801e-01 +-3.1350464229561110e+00 +9.5554832578698068e-01 +2.6366759893779512e-01 +-3.1429699957846031e+00 +6.2756002082809681e-01 +2.3372424622239044e-01 +-2.7773793485575577e+00 +9.5006814361123870e-01 +2.6733694504883387e-01 +-3.1384950751723077e+00 +9.3106856751825251e-01 +2.7435919162227052e-01 +-3.1093312579649770e+00 +9.3071599864685117e-01 +2.7404967284116299e-01 +-3.1072893067455274e+00 +5.9153006465248925e-01 +2.4253063510570519e-01 +-2.7501379425959116e+00 +7.5844682514197015e-01 +2.5837159848895758e-01 +-2.9051819886676129e+00 +8.4077399323143776e-01 +2.6803003687346250e-01 +-2.9861502765986669e+00 +8.2668021828115268e-01 +2.6793385460872965e-01 +-2.9706041461507953e+00 +7.5383668869024989e-01 +2.6386061435341213e-01 +-2.9007278028500725e+00 +9.6248531205118659e-01 +2.8770699548192530e-01 +-3.1444427479785744e+00 +7.6947412895189249e-01 +2.7092791994010718e-01 +-2.9225833742089198e+00 +7.6947412895189249e-01 +2.7092791994010718e-01 +-2.9225833742089198e+00 +7.3417391914990793e-01 +2.7168180594766528e-01 +-2.8914124094822453e+00 +6.3847341049205397e-01 +2.6388868512671365e-01 +-2.7961665460319680e+00 +7.7632775540049936e-01 +2.8161690673359102e-01 +-2.9207240205059199e+00 +7.7632775540049936e-01 +2.8161690673359102e-01 +-2.9207240205059199e+00 +5.7232769896024549e-01 +2.6369732344747021e-01 +-2.7289082975354324e+00 +8.3974648364756221e-01 +2.8989187490955626e-01 +-2.9724093849750544e+00 +8.3974648364756221e-01 +2.8989187490955626e-01 +-2.9724093849750544e+00 +-8.9176713357933213e-01 +2.5305258004722408e-01 +-2.4893344171508582e+00 +9.4333342736142367e-01 +3.1200822974928244e-01 +-3.1233566234806811e+00 +9.4925242440136237e-01 +3.1351640846730922e-01 +-3.1255729763980584e+00 +-1.1414465646162339e+00 +2.4968981169071824e-01 +-2.3821964700638025e+00 +1.3251801660520972e+00 +2.4803436012507432e-01 +-2.3896450236009601e+00 +9.3628664060117783e-01 +3.2071047705545686e-01 +-3.1004630101219890e+00 +-7.9733776251683697e-01 +2.7784515897635353e-01 +-2.5847318837665432e+00 +1.3515602648577627e+00 +2.5037535722755233e-01 +-2.3405470888528797e+00 +9.4959744604394092e-01 +3.3293253572579634e-01 +-3.1114434675139435e+00 +5.2018915341476413e-01 +2.8875576941650677e-01 +-2.6763019143703040e+00 +4.7900914862239086e-01 +3.0999136208446842e-01 +-2.6680871420146768e+00 +4.5133778427487076e-01 +3.2950862093693278e-01 +-2.6626041339004680e+00 +8.6346220482213898e-01 +4.0272916909435980e-01 +-3.1799087342991030e+00 +-1.2995243653412845e+00 +3.2616834612385170e-01 +-2.3996364847126004e+00 +-1.3423713690673624e+00 +3.3238194195095833e-01 +-2.4090325640856238e+00 +7.2934739313629038e-01 +4.0660933859935411e-01 +-3.0316122147597580e+00 +4.7776987332990151e-01 +3.5577118356599152e-01 +-2.6704109226268784e+00 +6.1508553836363378e-01 +3.7041967887286414e-01 +-2.7626793873084892e+00 +7.1984483356579798e-01 +4.1019313940471508e-01 +-3.0133818867235465e+00 +5.8867510291414449e-01 +3.7218787808633025e-01 +-2.7370833031880180e+00 +5.7444202578287218e-01 +3.7403490666432099e-01 +-2.7294514110034402e+00 +5.5601283139688928e-01 +3.7384104442674598e-01 +-2.7059198819464467e+00 +5.3640748240293767e-01 +3.7244175253447148e-01 +-2.6936006160564916e+00 +5.6176257731347090e-01 +3.7713839326940385e-01 +-2.7098783636882633e+00 +5.2875931598879722e-01 +3.7395934089621768e-01 +-2.6795279677630348e+00 +5.5490972852643095e-01 +3.7831520640541300e-01 +-2.7066044967824379e+00 +5.2212490503656384e-01 +3.8647602760625777e-01 +-2.6921821441733464e+00 +6.0852957174321720e-01 +4.0576452011067260e-01 +-2.7638573902089298e+00 +5.3497512030691141e-01 +4.0041469452011247e-01 +-2.6982746944211953e+00 +-7.3281838162376778e-01 +4.1303784060496845e-01 +-2.6921412499651014e+00 +5.9483021045508766e-01 +4.4225578865342097e-01 +-2.7495664526479651e+00 +5.7944549853680161e-01 +4.4245884539972158e-01 +-2.7314620682517043e+00 +5.1263779264108444e-01 +4.4619392673471281e-01 +-2.6817414919784661e+00 +1.7925561523610649e+00 +5.3809800970095334e-01 +-3.0992627562164556e+00 +4.6498669530251358e-01 +4.5748987039782640e-01 +-2.6919259506223208e+00 +-7.9357882222787990e-01 +4.6423112382628684e-01 +-2.5866060390646162e+00 +-9.7946367479560026e-01 +4.9210637136845126e-01 +-2.4357075841057196e+00 +-1.3619162736057511e+00 +5.0078288657647951e-01 +-2.4093433736669914e+00 +-6.7660007331057526e-01 +6.0820000776020933e-01 +-2.9706381107526321e+00 +-7.2983687836022881e-01 +5.6376187558988511e-01 +-2.7067250113881527e+00 +-7.1575193681162619e-01 +5.9367206979066556e-01 +-2.7222101520526447e+00 +-1.1631044346842332e+00 +5.6178434161726032e-01 +-2.3970136727322209e+00 +-7.9183003853497669e-01 +6.0031541390006959e-01 +-2.5924602438818631e+00 +-9.8550973280611798e-01 +6.0950711412199476e-01 +-2.4343866714150515e+00 +-8.8759235179441820e-01 +6.3604252505161962e-01 +-2.4963992841203004e+00 +-9.4725405836668808e-01 +6.4894377145623960e-01 +-2.4658380202268164e+00 +-9.9977607955837200e-01 +6.4832127702560316e-01 +-2.4329076379133090e+00 +-1.1598429093981804e+00 +6.5252274624547180e-01 +-2.3922339045627075e+00 +-9.4392467006106384e-01 +7.9250195614666563e-01 +-2.6042173695438882e+00 +-1.2099769118550781e+00 +8.3838740866836503e-01 +-2.4467553974628498e+00 +8.2073477616497437e-01 +-3.5455725321072509e-02 +-2.9848183013959395e+00 +-1.1264856700934556e+00 +1.8904245795659802e-02 +-2.3747249540311777e+00 +9.5645742944259371e-01 +2.1447420299257478e-02 +-3.1377932287570549e+00 +6.2304135211092693e-01 +7.2074542612507911e-02 +-2.7791574593140966e+00 +1.5614422873099392e+00 +1.0589743838279114e-01 +-3.9463218771600888e+00 +1.0079733624186038e+00 +8.8696744397647409e-02 +-3.2248019180193022e+00 +1.0465020118633681e+00 +1.0079784440812314e-01 +-3.2423194301830454e+00 +1.5823065656025035e+00 +1.3411782733824892e-01 +-4.0190407721481449e+00 +1.1528005146914284e+00 +1.2403997459626280e-01 +-3.4038179412103977e+00 +1.2580602787893969e+00 +1.3663760726685925e-01 +-3.5422512354107631e+00 +9.4905696339267021e-01 +1.4172277124326849e-01 +-3.1437271280851786e+00 +1.1762275722759998e+00 +1.7574296635283293e-01 +-3.4226460634975275e+00 +1.0706832330506961e+00 +1.7668862409023306e-01 +-3.2760196241005266e+00 +1.0746697044237181e+00 +1.7820483709653820e-01 +-3.2740459310006793e+00 +1.0480148720476599e+00 +1.7671262638508631e-01 +-3.2360827110599768e+00 +9.7701398435484121e-01 +1.7335078085142977e-01 +-3.1617700341997867e+00 +9.8788287942102126e-01 +1.8036805215852611e-01 +-3.1771315471469963e+00 +1.2729722586990433e+00 +2.0968076442460518e-01 +-3.5648318316616825e+00 +8.7145105719826699e-01 +1.8284827734626716e-01 +-3.0392543640800720e+00 +8.8635034733900198e-01 +1.8645454395337874e-01 +-3.0568637494228690e+00 +5.6562025489052259e-01 +1.6632852267286463e-01 +-2.7159667993781094e+00 +1.0730332399987337e+00 +2.0351684792448199e-01 +-3.2823955270756726e+00 +1.1126607144179228e+00 +2.0805387464780103e-01 +-3.3362434912058934e+00 +7.2407508314198177e-01 +1.9058566011459308e-01 +-2.8897537543343610e+00 +1.3451679435667219e+00 +1.5816398240543270e-01 +-2.3358434431269366e+00 +7.0146291246997217e-01 +1.9781412529845066e-01 +-2.8710249674998556e+00 +7.0320656207173460e-01 +2.0074431885979840e-01 +-2.8672257195161630e+00 +1.3616827757279022e+00 +1.9326185790379616e-01 +-2.6007927316301767e+00 +1.1345969138291625e+00 +2.5870342691407527e-01 +-3.3739424664937516e+00 +9.9935207709682816e-01 +2.4466263726182477e-01 +-3.1982262383568769e+00 +1.3025790197145553e+00 +2.8075846624810880e-01 +-3.6366557659548473e+00 +-9.2174850567439526e-01 +2.0063738893831412e-01 +-2.4744536730311184e+00 +1.0744704444096558e+00 +2.6303450315133409e-01 +-3.2630678475765835e+00 +1.0440990655944926e+00 +2.6110654761949836e-01 +-3.2217294805752612e+00 +8.3867257802579609e-01 +2.4648161435818577e-01 +-2.9775560270203152e+00 +8.2951384506057346e-01 +2.4707885923775857e-01 +-2.9792838647413813e+00 +1.0287892718787646e+00 +2.7330846708042161e-01 +-3.2282478176311131e+00 +7.9462439388671002e-01 +2.5033028041217226e-01 +-2.9315477537804386e+00 +8.3297368278350470e-01 +2.6653677841834278e-01 +-2.9717998095627198e+00 +1.3270252847684578e+00 +2.2128826859669753e-01 +-2.4136240889453164e+00 +7.5018075891397029e-01 +2.7205371210218288e-01 +-2.9048100647533515e+00 +5.4187391292413345e-01 +2.5402345684534622e-01 +-2.7016652283522542e+00 +5.3842443661629991e-01 +2.5785129546070690e-01 +-2.7023617526500932e+00 +1.3928502387962691e+00 +2.2325808678327966e-01 +-2.3005664817051992e+00 +1.3314926751642702e+00 +2.3217567328642222e-01 +-2.3991340536878885e+00 +9.0662060088781049e-01 +3.0235201866196226e-01 +-3.0896461602771654e+00 +8.6273261433218351e-01 +3.3117054341506152e-01 +-3.1592918036721001e+00 +7.2811845027281230e-01 +3.1402570437099281e-01 +-2.9341932922204617e+00 +1.3806535515402423e+00 +2.5626730646636142e-01 +-2.3539229677941944e+00 +1.3277861000166358e+00 +2.5701722370190522e-01 +-2.3605569546583118e+00 +5.5986797645104047e-01 +2.9387203781315657e-01 +-2.7181669716094210e+00 +4.8778599375848292e-01 +2.8978906030273466e-01 +-2.6581725069333531e+00 +1.3756052191718706e+00 +2.5456339131583561e-01 +-2.2806520618020625e+00 +1.3756052191718706e+00 +2.5456339131583561e-01 +-2.2806520618020625e+00 +-7.6646329874339336e-01 +3.2554549731757404e-01 +-2.8861290836002840e+00 +9.1427107528936635e-01 +3.6250628524595674e-01 +-3.1014911404742502e+00 +1.3456556044029240e+00 +2.8842091599213154e-01 +-2.3497203050006519e+00 +1.3741195183530350e+00 +2.8890546184521254e-01 +-2.3219264765380285e+00 +1.3741195183530350e+00 +2.8890546184521254e-01 +-2.3219264765380285e+00 +8.6297974938830135e-01 +3.9667412163724425e-01 +-3.1748452556948141e+00 +6.2651682969278544e-01 +3.4910104979853407e-01 +-2.7832574419202634e+00 +1.4058408129300706e+00 +2.9995065133393944e-01 +-2.3009837267514195e+00 +1.4058408129300706e+00 +2.9995065133393944e-01 +-2.3009837267514195e+00 +7.9925658263087584e-01 +4.1330839779830492e-01 +-3.2034579555685818e+00 +5.1408872927119087e-01 +3.5719054753774016e-01 +-2.6786089939095259e+00 +4.4715313711788696e-01 +3.5704328602075819e-01 +-2.6647513082191798e+00 +5.5653150028396692e-01 +3.6943642370330565e-01 +-2.7017150920010549e+00 +4.8347545038915785e-01 +3.7246985926352921e-01 +-2.6576284333468805e+00 +1.4824774405024379e+00 +3.6341968179873901e-01 +-2.5285961634727214e+00 +6.3604200067658512e-01 +4.1078725843569519e-01 +-2.8125715484592093e+00 +5.8799012999898237e-01 +4.5228517929981310e-01 +-2.7419327845134833e+00 +5.8799012999898237e-01 +4.5228517929981310e-01 +-2.7419327845134833e+00 +5.7572415324140869e-01 +4.5005736697622428e-01 +-2.7256623251256498e+00 +-8.9502098006610742e-01 +4.2736508664411277e-01 +-2.4926631409131517e+00 +5.1802818203605061e-01 +4.5322597707944873e-01 +-2.6868110166557866e+00 +4.9166742801828200e-01 +4.5114987556007080e-01 +-2.6755167336218810e+00 +4.8833697019958944e-01 +4.5706761409246305e-01 +-2.6809498482729208e+00 +4.0563880570980793e-01 +4.6548649236335354e-01 +-2.6435402664385026e+00 +-7.4222959814621015e-01 +4.8485982980387315e-01 +-2.6639706491825388e+00 +-1.2441375740044835e+00 +7.3749162974199911e-01 +-2.4035474625656859e+00 +2.8600729717751872e-01 +-4.8190320352548964e-02 +-7.5045352368671925e-01 +9.4681048268697110e-01 +1.4708144291749267e-01 +-3.1352810217477174e+00 +1.0927052721997634e+00 +1.5848828723113301e-01 +-3.3015195455840809e+00 +1.8250461006753889e+00 +2.2834560573591978e-01 +-4.4359186785870950e+00 +1.1862435457564839e+00 +1.7762702814840794e-01 +-3.4405264821632886e+00 +1.0752437901587075e+00 +1.7110992078733622e-01 +-3.2755939994842826e+00 +8.7757190322678780e-01 +1.8146067632245863e-01 +-3.0493669114231032e+00 +1.0697065285296325e+00 +2.4118410593683337e-01 +-3.2727956354990946e+00 +1.3124052029347344e+00 +2.8414034932722415e-01 +-3.6274075484219268e+00 +1.3186978696065212e+00 +1.9585909737963353e-01 +-2.4435486611145016e+00 +1.3162688764945449e+00 +1.9731912475797617e-01 +-2.4361932518906340e+00 +1.3277942679158132e+00 +2.0128520242337819e-01 +-2.3603597373242149e+00 +9.3812959347897373e-01 +2.8484192748677073e-01 +-3.1236997893710807e+00 +1.3266608010952563e+00 +3.5908553374731489e-01 +-3.7385105884851226e+00 +9.3175055684888475e-01 +3.2319388026454532e-01 +-3.1007078761337734e+00 +9.5776537682875407e-01 +3.3748779435271065e-01 +-3.1268558272596940e+00 +5.5052508459011795e-01 +2.9628143193036638e-01 +-2.6982875382697018e+00 +1.3234839751397189e+00 +2.8543124905298128e-01 +-2.3995233389572599e+00 +1.3252898290665553e+00 +2.8955660578057130e-01 +-2.3982620429568748e+00 +1.3255434340225560e+00 +2.9328409590572385e-01 +-2.3987533945932773e+00 +5.3861529038005718e-01 +3.3516629225081063e-01 +-2.6991915052594821e+00 +1.3403075705907288e+00 +3.0215797166583142e-01 +-2.3493130765858514e+00 +8.3450805757563751e-01 +4.1367915137285027e-01 +-3.1729243275613648e+00 +4.1891032234310155e-01 +3.4580554457969365e-01 +-2.6439179151753982e+00 +1.5236866915966212e+00 +3.6569797514706720e-01 +-2.5182503527546691e+00 +6.2561753820024824e-01 +4.5390086547046421e-01 +-2.8214710901646911e+00 +1.3101932739080719e+00 +-1.7414340334061182e-02 +-2.4194781331070336e+00 +4.4172923949611009e-01 +3.9584993908755078e-01 +-2.6623430330048889e+00 +4.4204881201600765e-01 +3.9600010763451865e-01 +-2.6629921852694047e+00 +1.3294606594621665e+00 +2.0516452241872716e-03 +-2.3969124478957675e+00 +1.3378823269066855e+00 +4.5368541987643847e-02 +-2.4094246266816475e+00 +3.8810622391711419e-01 +4.0458699152423228e-02 +-2.6441036483443026e+00 +1.3750790844515164e+00 +1.2796551113646173e-01 +-2.6039828177799995e+00 +5.3254282102730666e-01 +1.3863637605298645e-01 +-2.6928167537695336e+00 +6.2890067950367412e-01 +1.7153821163266048e-01 +-2.7841212316167243e+00 +1.4231016134541732e+00 +1.8806236370822693e-01 +-2.2664236446723773e+00 +5.3080000826499218e-01 +3.3849994440991343e-01 +-2.6985034292384626e+00 +3.9316191892333424e-01 +3.4217475510485962e-01 +-2.6601708950646863e+00 +4.4949359363111963e-01 +-2.5017522262882619e-02 +-2.6498852065907612e+00 +1.3813798545738900e+00 +-1.4073061291204407e-02 +-2.6058534037588319e+00 +1.3745813483591762e+00 +4.2002788208935944e-02 +-2.5989510147778150e+00 +1.3293548462663720e+00 +4.6220602334093142e-02 +-2.4434177546586366e+00 +1.3293548462663720e+00 +4.6220602334093142e-02 +-2.4434177546586366e+00 +1.3750686129418452e+00 +2.3821329496002072e-01 +-2.6046403246359460e+00 +1.3295532440359326e+00 +2.0684025467037234e-01 +-2.3813309314131259e+00 +1.3261534544636377e+00 +2.6718104170187501e-01 +-2.4396238710545872e+00 +4.4357418850545371e-01 +2.4492025295401643e-01 +-2.6565904279241597e+00 +3.7113833213623065e-01 +2.6039302494995359e-01 +-2.6549383485131091e+00 +4.6644675717405143e-01 +2.8213024378916485e-01 +-2.6563761254057168e+00 +3.7415455341736509e-01 +3.5906199665920968e-01 +-2.6543839261655893e+00 +4.0151452577313035e-01 +3.7211910456145064e-01 +-2.6467413201762930e+00 +3.1369242025062882e-01 +3.7649763018226040e-01 +-2.6587839271258873e+00 +1.3048839337366753e+00 +-6.1783536931115539e-02 +-2.4290675833425333e+00 +1.3271500012359285e+00 +-4.7358984399099108e-02 +-2.4340481999416634e+00 +1.4545366482838897e+00 +-4.2822825704982553e-02 +-2.2183283905056870e+00 +1.3315687318344696e+00 +1.8097005886685516e-02 +-2.3750687068593410e+00 +9.9883588237842957e+00 +7.3536810295281152e-01 +-1.5438967653571197e+01 +7.5588328132653904e-01 +7.7895180953023196e-02 +-2.8872967458396297e+00 +4.0365370145055052e-01 +6.0171659678795203e-02 +-2.6461549893018197e+00 +3.7262371511473857e-01 +5.9633199508441391e-02 +-2.6432117447985650e+00 +3.1458751525902373e-01 +7.3915382658517784e-02 +-2.6661850922324670e+00 +8.0007719013064216e-01 +1.5531133301231767e-01 +-2.9275918178442875e+00 +1.3898189482781069e+00 +1.7588555649416251e-01 +-2.6456919840116986e+00 +8.8521400672282147e-01 +1.9531127481733068e-01 +-3.0485369740127153e+00 +1.3354368622637032e+00 +1.7994540726276076e-01 +-2.4875882580204736e+00 +1.3810433210969124e+00 +1.7022706016169667e-01 +-2.2976163477518465e+00 +1.3809111905992553e+00 +1.7025384122096479e-01 +-2.2975702822244042e+00 +1.3366480505902765e+00 +2.4441414334453726e-01 +-2.4127705719893244e+00 +3.5939892828435349e-01 +2.7011255615851409e-01 +-2.6578158753285837e+00 +5.2257251341145894e-01 +3.0154109618206881e-01 +-2.6889113663832878e+00 +4.1641039051250833e-01 +3.0459532254815991e-01 +-2.6730262785339076e+00 +5.0632298093835781e-01 +3.4553426951246069e-01 +-2.6851477963282462e+00 +5.6287697730595898e-01 +3.7093667900177119e-01 +-2.7219349965849591e+00 +5.9586278429436268e-01 +3.8448114366613534e-01 +-2.7611892745421067e+00 +4.1041024115739427e-01 +3.5829288307402202e-01 +-2.6579618729280314e+00 +4.0956615603244922e-01 +3.5798005226489510e-01 +-2.6549437722611673e+00 +4.1944167473659616e-01 +3.7315830967184910e-01 +-2.6495505856759149e+00 +3.3112295490746568e-01 +4.0182050383668433e-01 +-2.6523956266340667e+00 +3.4362345645497239e-01 +4.1405702670869432e-01 +-2.6542783937555350e+00 +5.9968205091955396e-01 +-8.8023512109413629e-02 +-2.7343371060986645e+00 +1.3289793293918177e+00 +-8.6818680928561168e-02 +-2.4543297538086182e+00 +3.9865054772708769e-01 +-5.7519739895510555e-02 +-2.6402283686145522e+00 +4.8594962234171335e-01 +-4.1356567772040352e-02 +-2.6591377886671137e+00 +4.1596368432135600e-01 +-3.9641775362364767e-02 +-2.6451082262955037e+00 +3.9562769322950131e-01 +-3.9527313167554208e-02 +-2.6465340976140999e+00 +3.8156504950821207e-01 +-3.9131287747149412e-02 +-2.6445632956781977e+00 +3.5690883508431936e-01 +-3.8539571583251629e-02 +-2.6315538409812897e+00 +4.3521627727531059e-01 +-3.7117098297893794e-02 +-2.6451719295109983e+00 +1.3232262786714519e+00 +-3.3371156270325102e-02 +-2.4361795670495558e+00 +5.4238888013346864e-01 +-2.9695218207629635e-02 +-2.6932209365963935e+00 +1.3461973880247753e+00 +-3.0691125703766888e-02 +-2.3370584673570765e+00 +1.4511153249979036e+00 +-2.9723839112737922e-02 +-2.2290122323363275e+00 +1.4385993568446014e+00 +-2.9294671797584656e-02 +-2.2426183638799859e+00 +4.0465785262321119e-01 +-2.6077098274122114e-02 +-2.6449503834214583e+00 +4.0403961808140815e-01 +-2.6640191649989042e-02 +-2.6417335318995931e+00 +4.1495594527224172e-01 +-2.5771456307572563e-02 +-2.6452608729913591e+00 +4.1507141224352734e-01 +-2.5986253800671343e-02 +-2.6460237283378096e+00 +3.5887686280433251e-01 +-2.3569286214531388e-02 +-2.6469225729168135e+00 +3.5909398996057884e-01 +-2.3750775096232298e-02 +-2.6481518834554856e+00 +1.4665119151253736e+00 +-1.7422052562479525e-02 +-2.2161356718896155e+00 +1.4536834502324891e+00 +-1.0058478660139871e-02 +-2.2280844327599834e+00 +6.1179500886859794e-01 +4.1131812400836555e-02 +-2.7723292740920722e+00 +9.7228938620148000e+00 +7.1714433909422981e-01 +-1.5550564854894892e+01 +1.4205586762038480e+00 +4.0044263016367418e-02 +-2.2779891653450552e+00 +7.8135625329242286e-01 +5.7146520064814813e-02 +-2.9304548824985401e+00 +5.9744877786252892e-01 +5.3585518281800797e-02 +-2.7565036199344166e+00 +5.6047293031386114e-01 +5.4585632802480008e-02 +-2.7071706501039468e+00 +5.5882303957288859e-01 +5.4234175284334801e-02 +-2.7022851513859623e+00 +1.3269173353290806e+00 +7.0220414159998010e-02 +-2.3901712523277707e+00 +4.2571003703191884e-01 +6.0063236202811419e-02 +-2.6471318885706117e+00 +4.2572782187271369e-01 +6.0029075186849350e-02 +-2.6472374296308163e+00 +5.4053064950385932e-01 +6.7115479727082594e-02 +-2.6880501700832595e+00 +1.0642695612569295e+00 +1.2143189398075062e-01 +-3.2517465827740728e+00 +4.4920684044923459e-01 +7.0065812735327124e-02 +-2.6408762100979164e+00 +4.3167510910886975e-01 +7.1351301454392724e-02 +-2.6434764971959490e+00 +3.7049997806253637e-01 +7.2242109036205662e-02 +-2.6389826048296228e+00 +9.1144619656851023e-01 +1.1837264988270711e-01 +-3.0852723375639171e+00 +4.0538509862331951e-01 +8.3239808157568526e-02 +-2.6510383236265982e+00 +4.0489837798483785e-01 +8.3075250720790056e-02 +-2.6493241440780051e+00 +3.7087132679540530e-01 +8.2669479261492998e-02 +-2.6507323663137052e+00 +8.6278278880923864e-01 +1.3229785734105784e-01 +-3.0012991408566121e+00 +4.4533137423494312e-01 +1.1269220377593318e-01 +-2.6498734762666243e+00 +4.4525193109065520e-01 +1.1261500253089012e-01 +-2.6495875142133762e+00 +4.0771915965902278e-01 +1.5173222988816215e-01 +-2.6535250130657859e+00 +1.4461856724636879e+00 +1.7165616126483724e-01 +-2.2504524865267941e+00 +6.0141870620867510e-01 +1.8245714909365954e-01 +-2.7586652717516622e+00 +4.1548342206535016e-01 +1.6898752343148452e-01 +-2.6418703126962719e+00 +3.6310568686664491e-01 +1.7319316947396243e-01 +-2.6522840664071126e+00 +1.3896229998682303e+00 +2.3640407864322538e-01 +-2.5940094865780483e+00 +1.4173933520436868e+00 +2.0842319871994242e-01 +-2.2802765416670407e+00 +1.3289952540750671e+00 +2.1794413558667408e-01 +-2.4014248072658577e+00 +6.8192259715594028e-01 +2.5044572372576440e-01 +-2.8246933075642682e+00 +5.0722072320954537e-01 +2.3612432696974958e-01 +-2.6821146241303997e+00 +4.2406362287850952e-01 +2.5481227334517492e-01 +-2.6480547781768622e+00 +4.2403795231671210e-01 +2.5485740164046716e-01 +-2.6481304882012204e+00 +8.6097812468732215e-01 +3.9792077190198055e-01 +-3.1506299743303154e+00 +1.8869802421896011e+00 +5.2758469746980252e-01 +-3.0419239743135975e+00 +3.3104446256015069e-01 +3.0393483717200265e-01 +-2.6512876184882299e+00 +6.1574358619424496e-01 +4.1971760620975918e-01 +-2.7783144843938063e+00 +3.1685211632924587e-01 +3.6001165075887565e-01 +-2.6658201882971184e+00 +3.4817699901789423e-01 +4.0415878701421243e-01 +-2.6663110924631277e+00 +3.9993872443525658e-01 +4.5000679401985422e-01 +-2.6582040540040328e+00 +3.8295223901343267e-01 +4.4780953308789234e-01 +-2.6486332377667798e+00 +3.7548401515780117e-01 +4.8065127011431397e-01 +-2.6249933149960647e+00 +8.4242722184838270e-01 +-1.4762871822961915e-01 +-3.0049051633405757e+00 +4.8333704686772522e-01 +-8.0326760864187566e-02 +-2.6685933045800594e+00 +4.2635477574030978e-01 +-4.7723361596320589e-02 +-2.6448981877305444e+00 +3.3393926622728021e-01 +-4.6318347130554050e-02 +-2.3289909907610604e+00 +5.7394300246648822e-01 +-4.5033846972528588e-02 +-2.7136145062953227e+00 +1.0487527631918936e+00 +-4.0730006378207492e-02 +-3.2371175034372071e+00 +1.3366857691272269e+00 +-3.6198015670975928e-02 +-2.4991770418536299e+00 +3.6885549086616642e-01 +-2.9619977948772774e-02 +-2.6428999449139075e+00 +3.4831998261616859e-01 +-2.9517204125437204e-02 +-2.6456462086299743e+00 +1.3412283878246773e+00 +9.6774166694452626e-03 +-2.4169530854674925e+00 +9.6335364157251178e+00 +4.6215033194392641e-01 +-1.5431523738365014e+01 +1.4331899079108665e+00 +2.9246798827553027e-02 +-2.2794646510689018e+00 +1.0232833923033995e+00 +5.7268378983624038e-02 +-3.2096631130671738e+00 +1.3318184556968129e+00 +4.6217682106384904e-02 +-2.4731413217469176e+00 +4.2740863427425368e-01 +3.7322794307120551e-02 +-2.6484265741460771e+00 +4.1710235853552585e-01 +3.7793091634234582e-02 +-2.6514423390987627e+00 +4.0638985230387403e-01 +3.8715573057527736e-02 +-2.6470153898581210e+00 +4.0608078333041797e-01 +3.8787586205465185e-02 +-2.6462584780944920e+00 +5.1505255220660806e-01 +4.6519053133464217e-02 +-2.6846524692011773e+00 +4.7422103730677445e-01 +4.7891710505176655e-02 +-2.6658522245458656e+00 +1.0601520662212320e+00 +9.7173471613479834e-02 +-3.2506754887925040e+00 +7.9069441420752884e-01 +8.1701995703688052e-02 +-2.9510971231533838e+00 +7.8742142431820727e-01 +8.1143603810997667e-02 +-2.9345465429314852e+00 +8.6959961752870152e-01 +1.0395436223499256e-01 +-3.0163235517459661e+00 +1.3929505151525854e+00 +1.0757634258794786e-01 +-2.5962346205528637e+00 +4.2601738841338810e-01 +8.2675908341507592e-02 +-2.6523997594888398e+00 +4.2577623323246794e-01 +8.2543509607838600e-02 +-2.6512001168150405e+00 +5.8372303429505179e-01 +1.0260536003018238e-01 +-2.7477623673961804e+00 +1.3464509554919921e+00 +1.0684434440735578e-01 +-2.3283844521086046e+00 +1.3464509554919921e+00 +1.0684434440735578e-01 +-2.3283844521086046e+00 +7.0844059901904743e-01 +1.2289273927374797e-01 +-2.8647442109785795e+00 +4.3714610596318909e-01 +1.0427564734429358e-01 +-2.6534628863861029e+00 +1.3683873603759591e+00 +1.5680764837572880e-01 +-2.5528108072128726e+00 +1.3313534131705935e+00 +1.5425851846994579e-01 +-2.4134967809459202e+00 +1.3305217185734919e+00 +1.5395557569679921e-01 +-2.4125026665499827e+00 +2.3234758586095547e+00 +3.4718513344989604e-01 +-3.9739885154459809e+00 +9.7314285529941602e-01 +2.1569565317790110e-01 +-3.1540003789479152e+00 +8.3504676892971519e-01 +1.9711303329495414e-01 +-2.9884985428124518e+00 +8.3413117807259185e-01 +1.9557008784992552e-01 +-2.9841915093870508e+00 +1.4492732210949080e+00 +1.5690557115716516e-01 +-2.2441989285960968e+00 +4.1933012862420893e-01 +1.4458584324318161e-01 +-2.6590445848565896e+00 +4.2583558161134766e-01 +1.5145618632913618e-01 +-2.6534779914666942e+00 +4.3433611900725178e-01 +1.5928575913393672e-01 +-2.6547341946064362e+00 +1.3511699715062648e+00 +2.0267223766450132e-01 +-2.5135392636789198e+00 +3.4526187101468625e-01 +1.6232803710329513e-01 +-2.6609843260852446e+00 +6.4862762054398659e-01 +2.2457353227659058e-01 +-2.8056943989828018e+00 +1.3560656408572365e+00 +2.5696108766541281e-01 +-2.3291101810173678e+00 +3.6333288549290799e-01 +2.3407839462088970e-01 +-2.6634058820207880e+00 +1.3241046714445277e+00 +3.0039095537256105e-01 +-2.4601721702169201e+00 +3.4495262224848572e-01 +2.4905985113432202e-01 +-2.6528361357339141e+00 +3.7891024003378776e-01 +2.7424125550535139e-01 +-2.6538200845119171e+00 +1.8436362369558004e+00 +5.1552519081659287e-01 +-3.0648374598493175e+00 +1.8414406982465121e+00 +5.3128235788170564e-01 +-3.0584247302093166e+00 +4.2715667305893779e-01 +3.4143665313153354e-01 +-2.6525468006218249e+00 +3.5453374601830728e-01 +3.4407720442234319e-01 +-2.6570145519503146e+00 +3.5103912918531577e-01 +3.5438054840510708e-01 +-2.6571889305295997e+00 +5.5964434841635602e-01 +4.0174590293161305e-01 +-2.7195533356227508e+00 +4.1039222660603764e-01 +4.0067840892351947e-01 +-2.6515752474772278e+00 +4.1062976237870025e-01 +4.4156958743897384e-01 +-2.6542026972025297e+00 +8.1001376608472087e-01 +-1.4580153969631066e-01 +-2.9582426978739584e+00 +1.3923850514180747e+00 +-1.1626201976857073e-01 +-2.5961205744048841e+00 +6.0118093744976853e-01 +-1.0162798176088403e-01 +-2.7501832896883243e+00 +5.7070229849707443e-01 +-8.9083641015987147e-02 +-2.7138029574633649e+00 +5.6750621682941094e-01 +-8.8658522644597074e-02 +-2.7055688428263838e+00 +5.5590647408372873e-01 +-8.2866180169323136e-02 +-2.6935809029159898e+00 +5.1072013852154463e-01 +-8.0576439348207907e-02 +-2.6841828892502377e+00 +5.1072013852154463e-01 +-8.0576439348207907e-02 +-2.6841828892502377e+00 +4.3290034583875492e-01 +-7.8672701884577825e-02 +-2.6440335056547211e+00 +5.7240078256144789e-01 +-5.9888361309168095e-02 +-1.8949637683536400e+00 +1.3977641275478634e+00 +-8.0597590457097565e-02 +-2.6002582080932357e+00 +1.2954943285156557e+00 +-7.5989949875484422e-02 +-2.4334376292684254e+00 +1.0420940576048801e+00 +-8.2540821351698032e-02 +-3.2257808639375631e+00 +1.3635107900296481e+00 +-7.0546826626245743e-02 +-2.3113745479591978e+00 +1.0668804326082202e+00 +-6.4863845292140954e-02 +-3.2542189544753022e+00 +4.7468949991994480e-01 +-4.9828186193471471e-02 +-2.6557348456871672e+00 +3.9193340420148476e-01 +-4.8415815635300612e-02 +-2.6455059231022653e+00 +3.7685831428612260e+00 +-1.8904631924419664e-02 +-7.6472835448061813e+00 +4.7553819157726807e-01 +-3.2462544579388207e-02 +-2.6556873805820986e+00 +4.2538514961419027e-01 +-3.0152351252534210e-02 +-2.6447034561386600e+00 +1.3526717986763788e+00 +-2.2102409382332076e-02 +-2.3304698517902374e+00 +1.3213835509599325e+00 +-1.7811640386700366e-02 +-2.4475940884568925e+00 +1.0461013366704510e+00 +5.0807783671106598e-03 +-3.2350925451045112e+00 +1.5629280625874922e+00 +2.9493612169165604e-02 +-3.9354262709301522e+00 +1.5629280625874922e+00 +2.9493612169165604e-02 +-3.9354262709301522e+00 +9.2868205442418683e-01 +2.6865120506300619e-02 +-3.0990307030863642e+00 +1.3920924342256074e+00 +2.0252016389285130e-02 +-2.5953180960229294e+00 +5.7519936574401154e-01 +3.2139388051958803e-02 +-2.7228882478573024e+00 +1.3815727708818581e+00 +5.0557550688858886e-02 +-2.5714261521163038e+00 +3.8305871557283999e+00 +3.1487083370968078e-01 +-7.8598157887014670e+00 +1.3949668547417859e+00 +5.6617547074829980e-02 +-2.6493529331619077e+00 +1.5125993699993294e+00 +1.0911894407536274e-01 +-3.8836478421676586e+00 +1.0501040543873796e+00 +8.3337270686161632e-02 +-3.2416252027700687e+00 +1.4054733080441346e+00 +5.2334706614379611e-02 +-2.2796957923579635e+00 +7.3852414305389302e-01 +6.7874327263584458e-02 +-2.8850588959156229e+00 +1.3226515895346429e+00 +7.3976341647829513e-02 +-2.4744010763117337e+00 +1.3226515895346429e+00 +7.3976341647829513e-02 +-2.4744010763117337e+00 +1.3926573624753595e+00 +8.3775444173070160e-02 +-2.5961314662927140e+00 +1.3194000724558983e+00 +7.7764821523790190e-02 +-2.3987729422528492e+00 +8.0124466017482254e-01 +9.3166064362629059e-02 +-2.9478556655381238e+00 +6.4953758190912614e-01 +9.9090219922992273e-02 +-2.7949397348536018e+00 +1.4537642089636811e+00 +9.4547145321599607e-02 +-2.2415330205516550e+00 +6.8494656876625426e-01 +1.1982843444772992e-01 +-2.8312968606897635e+00 +1.0564757118291555e+00 +1.8101913124090346e-01 +-3.2467148317253778e+00 +1.3894657294025465e+00 +1.5328808967487303e-01 +-2.5932451676003105e+00 +1.3320979215717637e+00 +1.4830229048085569e-01 +-2.3601984132695764e+00 +1.3322665254531079e+00 +1.4823868114172528e-01 +-2.3602802828474170e+00 +6.0026772495931935e-01 +1.5440339421190041e-01 +-2.7576239038024659e+00 +1.4507344400177900e+00 +1.5652744091530407e-01 +-2.2350235375245986e+00 +3.6100634950309368e-01 +1.4205396434925360e-01 +-2.6644606964089168e+00 +3.6100634950309368e-01 +1.4205396434925360e-01 +-2.6644606964089168e+00 +9.1775921601187749e-01 +2.1384063896375408e-01 +-3.0874307389407520e+00 +7.6258797585949278e-01 +1.9394668755460273e-01 +-2.9239871960141861e+00 +5.9751475201351323e-01 +1.7372736072831624e-01 +-2.7560740427823265e+00 +4.1972696402170651e-01 +1.6038319332651282e-01 +-2.6492921349069967e+00 +1.3177842467595859e+00 +1.9426623488208278e-01 +-2.4420916526657321e+00 +1.3248278222265764e+00 +1.9917479825317830e-01 +-2.4644776530937671e+00 +1.4277316070648238e+00 +2.0328997427889828e-01 +-2.2671772652563433e+00 +1.4524146553050450e+00 +2.0395844059411006e-01 +-2.2354357608638602e+00 +4.2585879453175773e-01 +1.8694015434628958e-01 +-2.6546660972229064e+00 +1.3887165945422140e+00 +2.4971520770715461e-01 +-2.5950616931865791e+00 +8.5158283664424961e-01 +2.6409031252446791e-01 +-2.9978803188791940e+00 +1.4246768400982777e+00 +2.1738851883069518e-01 +-2.2764662399296869e+00 +1.3442612684723938e+00 +2.5487570174003332e-01 +-2.4955749333965089e+00 +9.6287786713774359e-01 +3.1360110784777956e-01 +-3.1366683200988890e+00 +6.7005717766503436e-01 +2.6853851927824940e-01 +-2.8254664191991563e+00 +1.4488794741542335e+00 +2.6210299569304218e-01 +-2.2542643724614431e+00 +9.4922399755654663e-01 +3.6419059978712820e-01 +-3.1286021715303409e+00 +1.3288586945512033e+00 +2.9882238676956946e-01 +-2.4517337634111409e+00 +3.7119759473649161e-01 +2.6322953888490408e-01 +-2.6537065784434497e+00 +3.5443834861548768e-01 +2.6653259007048119e-01 +-2.6589624082234224e+00 +3.0278942177005963e-01 +2.7298934360938176e-01 +-2.6651659728700645e+00 +1.9174852424247906e+00 +5.1369690152545899e-01 +-3.0481327082813960e+00 +1.9169151056076754e+00 +5.1345142935661170e-01 +-3.0473370619619859e+00 +1.8791909847077843e+00 +5.0930720080500991e-01 +-3.0316271979253493e+00 +1.8316461332433600e+00 +5.5039367357490987e-01 +-3.0847773217495598e+00 +4.1649918851668549e-01 +3.5051364870834739e-01 +-2.6547400476747702e+00 +3.7856681913375911e-01 +3.6049838688499808e-01 +-2.6565568691402430e+00 +3.3180445939435510e-01 +3.5715596407924693e-01 +-2.6580208705295618e+00 +3.0313612810038709e-01 +3.5776836167687043e-01 +-2.6747329659575358e+00 +5.8703327123387306e-01 +4.0833260910653596e-01 +-2.7522435413352366e+00 +3.5030692191451590e-01 +4.1200020283628458e-01 +-2.6553790208075680e+00 +3.4059760631288055e-01 +4.1103347073239249e-01 +-2.6571558188719289e+00 +3.5515990079462018e-01 +4.1851026708326361e-01 +-2.6489555117861312e+00 +4.1870219292113192e-01 +4.4830523950929674e-01 +-2.6561483395446035e+00 +3.6497747097096594e-01 +4.5612768930534370e-01 +-2.6538584545410848e+00 +4.5376532572667005e-01 +-1.4112102439351584e-01 +-2.6168811137252659e+00 +1.3931312800651525e+00 +-1.4464106554604697e-01 +-2.5960064347362861e+00 +5.9442209008524183e-01 +-9.3612493472223557e-02 +-2.7355729810499634e+00 +5.9066716431376232e-01 +-8.9800057565530833e-02 +-2.7398640440083688e+00 +5.0464373739100732e-01 +-8.6732958768805157e-02 +-2.6779319492992770e+00 +9.3570454342489495e-01 +-1.0125051357578907e-01 +-3.0895495796683878e+00 +9.2159251730476743e-01 +-9.8483436973045124e-02 +-3.0862857484943182e+00 +6.1268913570304173e-01 +-8.5865738995883401e-02 +-2.7584987717578460e+00 +1.5772597806333424e+00 +-1.0762006544293778e-01 +-3.9476674557879181e+00 +1.2853333690548046e+00 +-7.1742316847260804e-02 +-2.3693263703526202e+00 +1.3247592702213371e+00 +-7.3980437476081934e-02 +-2.4347164280861451e+00 +1.3337870595582935e+00 +-7.0903435116036237e-02 +-2.3431139770601002e+00 +1.3324325201548699e+00 +-7.2175007733854962e-02 +-2.3905596199762762e+00 +1.3423984682123768e+00 +-7.0679245375249139e-02 +-2.3327451317713419e+00 +8.5395131531414736e-01 +-7.4109117794317364e-02 +-3.0114765089891686e+00 +1.3976925838422662e+00 +-7.1188409930339994e-02 +-2.6000699546856145e+00 +9.3376082051808729e-01 +-7.1742256346293720e-02 +-3.0903457368557312e+00 +4.6086028876830931e-01 +-6.1666422888505310e-02 +-2.6532158977809788e+00 +1.3298872896462359e+00 +-6.5770902356345196e-02 +-2.3462320750625061e+00 +1.3332240976497394e+00 +-6.6785561099509880e-02 +-2.3746332838121584e+00 +1.3158703585881839e+00 +-6.6137664179293731e-02 +-2.3564531435659131e+00 +1.3940851761602939e+00 +-6.4177407692023625e-02 +-2.6047035759004551e+00 +9.1833919118561791e-01 +-6.4316955775673118e-02 +-3.0913547509538204e+00 +5.7948203776392260e-01 +-5.4532639870747641e-02 +-2.7282083758382329e+00 +1.3957800811848617e+00 +-5.7641525803592178e-02 +-2.5983261667662068e+00 +5.9649471948615063e-01 +-5.0005691206201547e-02 +-2.7381625321628986e+00 +3.5776544880327998e-01 +-4.8024170519406571e-02 +-2.6432488186588210e+00 +1.2995769428768700e+00 +-4.9413558891399575e-02 +-2.4069966431758414e+00 +4.3460523594232775e-01 +-4.5269033811725035e-02 +-2.6469986700879180e+00 +1.3873935589330511e+00 +-3.7942370637748794e-02 +-2.5992563513473299e+00 +1.5731413349171686e+00 +-2.2345966280798310e-02 +-3.9377450363491842e+00 +1.3162428891162399e+00 +-2.9358683525940454e-02 +-2.4395298860089056e+00 +3.8696053509805508e+00 +8.2043744774703484e-03 +-7.7924910127390303e+00 +1.3971951286497275e+00 +-2.4180743364234106e-02 +-2.5997931086650881e+00 +1.4372049033245231e+00 +-2.6956842764811823e-02 +-2.2456832705719592e+00 +1.5120302998136470e+00 +-8.1433942775832307e-03 +-3.8477068082819641e+00 +4.5607212778604206e-01 +-2.1985593042760189e-02 +-2.6475021685015818e+00 +1.3429312281299011e+00 +-1.5224247892404988e-02 +-2.4960399940729374e+00 +1.5353477701800706e+00 +3.6858548712975100e-02 +-3.9105143601194592e+00 +7.9990245852416764e-01 +1.4699675073961950e-02 +-2.9454301494771977e+00 +1.3274843107410910e+00 +1.4715073261832841e-02 +-2.3865728913929587e+00 +9.8828986447949108e-01 +3.5298787662025516e-02 +-3.1625646562223113e+00 +1.6704264016921533e+00 +4.9567830436532519e-02 +-3.0709704188776397e+00 +1.6191145816975001e+00 +8.4333926928221781e-02 +-4.0034209730470511e+00 +3.8298866629559503e+00 +2.8722131820952507e-01 +-7.8059285551009312e+00 +1.5981622354664038e+00 +1.3451383808018494e-01 +-4.0030611067217956e+00 +1.3907165667276098e+00 +6.7063913896614175e-02 +-2.5941856065654134e+00 +1.4191301416995508e+00 +5.2351506573413857e-02 +-2.2605715272562534e+00 +1.0255224056234824e+00 +8.9309391621093151e-02 +-3.2131076957431732e+00 +1.3695446681778114e+00 +6.6880269275886514e-02 +-2.5484701627981328e+00 +1.3881225083958519e+00 +6.9682909819183569e-02 +-2.5803308457140757e+00 +1.3888220163322460e+00 +6.9814699731354221e-02 +-2.5810800006426549e+00 +1.5763624670065075e+00 +1.4396469444890705e-01 +-3.9840631375871181e+00 +5.5875975575850167e-01 +5.8619766567496887e-02 +-2.7111695332647505e+00 +7.3970878387036421e-01 +7.6307912730732924e-02 +-2.8866831741344186e+00 +4.4250602421305235e-01 +6.3533788369577890e-02 +-2.6508551961776754e+00 +7.3399713544729106e-01 +1.1716903487076265e-01 +-2.8799966416820872e+00 +1.2601673354052065e+00 +1.9198127035750387e-01 +-3.5286378451611022e+00 +1.2671139855104216e+00 +1.9341774860285177e-01 +-3.5429532497305960e+00 +1.1766927258498165e+00 +1.9994798197309621e-01 +-3.4197843172346465e+00 +3.4026651559764060e-01 +1.0788124794410742e-01 +-2.6590122629805055e+00 +1.3296446687119103e+00 +1.3427665226393601e-01 +-2.3930221193022239e+00 +1.3260285523014947e+00 +1.5472489384367716e-01 +-2.3885737036812742e+00 +1.3234653210123679e+00 +1.5399874245528827e-01 +-2.3866302864337303e+00 +1.4389344389060337e+00 +1.4982891406568402e-01 +-2.2522193859227819e+00 +1.4389344389060337e+00 +1.4982891406568402e-01 +-2.2522193859227819e+00 +9.4157900148976392e-01 +2.2047988615515715e-01 +-3.1148173660205218e+00 +1.0829989614609534e+00 +2.5194063781093085e-01 +-3.2801990579490026e+00 +1.0387777770043813e+00 +2.5284469354937028e-01 +-3.2233160494766810e+00 +7.2705773659440143e-01 +2.0533072512269993e-01 +-2.8939672552518245e+00 +4.8008613758148555e-01 +1.6592012211541673e-01 +-2.6652396559319196e+00 +4.8008613758148555e-01 +1.6592012211541673e-01 +-2.6652396559319196e+00 +6.9937570245278924e-01 +2.0439804169297168e-01 +-2.8620702928709574e+00 +1.3115968749457214e+00 +1.9173403352600674e-01 +-2.4028458732537192e+00 +9.6004856487125712e-01 +2.5672804988934667e-01 +-3.1406981234393974e+00 +7.5500666034660990e-01 +2.2213747040523149e-01 +-2.9059087168236464e+00 +3.5065115200405544e-01 +1.6840891308156344e-01 +-2.6546381007686022e+00 +1.3279575381772761e+00 +1.9434286989395122e-01 +-2.3464721070776648e+00 +1.3203338824272446e+00 +1.9952996013675503e-01 +-2.3596717725399530e+00 +1.4407619511538525e+00 +1.9596974782823737e-01 +-2.2446689147618835e+00 +7.2472606543478757e-01 +2.2425091699345887e-01 +-2.8822285834553476e+00 +7.8986336470980734e-01 +2.3753171556657374e-01 +-2.9367752745371432e+00 +7.9456353939368407e-01 +2.3936202550220551e-01 +-2.9472154625339950e+00 +7.6574214773914306e-01 +2.4089720460104375e-01 +-2.9352094169083589e+00 +1.3700969378357308e+00 +2.5137527248813635e-01 +-2.6057610318717019e+00 +1.3939906138536053e+00 +2.5788548891641233e-01 +-2.5892025661138760e+00 +1.3362080313288580e+00 +2.4440506807031759e-01 +-2.4807309616407163e+00 +9.2037774802402295e-01 +3.0054286529567165e-01 +-3.0923608811783994e+00 +6.4923216662607108e-01 +2.4251550722585058e-01 +-2.8000745268465512e+00 +7.3612099859529612e-01 +2.6050866996882105e-01 +-2.8794251769215458e+00 +7.7758864729363142e-01 +2.7517525578651880e-01 +-2.9276110149440577e+00 +1.3185060970877205e+00 +2.6287891763343485e-01 +-2.4498394977922451e+00 +1.4561816988991543e+00 +2.6949679947871780e-01 +-2.2478382993940627e+00 +4.1075040680356167e-01 +2.6467251579467954e-01 +-2.6583524211104161e+00 +6.0693969462514108e-01 +3.8265419850474308e-01 +-2.7703582049431943e+00 +6.0693969462514108e-01 +3.8265419850474308e-01 +-2.7703582049431943e+00 +3.5871709567762283e-01 +3.5086498077828698e-01 +-2.6572508300936053e+00 +4.2224392291476015e-01 +3.6182436284707525e-01 +-2.6581076872874858e+00 +3.5816076607809111e-01 +3.6243585473479889e-01 +-2.6566155268956209e+00 +3.5814526326100038e-01 +3.6239550856736635e-01 +-2.6564616324134680e+00 +3.4110442213711328e-01 +3.7485810849619239e-01 +-2.6580276509535463e+00 +2.9896187928937329e-01 +4.1652276455516968e-01 +-2.6683466890029277e+00 +3.8601739980277566e-01 +4.6888329195080503e-01 +-2.6487049229168838e+00 +3.9195198318604224e-01 +4.9640142918586733e-01 +-2.6556519750390644e+00 +3.9195198318604224e-01 +4.9640142918586733e-01 +-2.6556519750390644e+00 +3.9910445230820152e-01 +-1.5035326404758192e-01 +-2.6498239611213408e+00 +5.8054547266166223e-01 +-9.8144684275574601e-02 +-1.8928674193425994e+00 +8.2986502985178501e-01 +-1.6061738936492959e-01 +-2.9826080208851025e+00 +5.6674711614322026e-01 +-9.3505759997780991e-02 +-1.8993798657694254e+00 +1.3901899602224586e+00 +-1.3096000351824358e-01 +-2.6004050459707488e+00 +1.3991748210259700e+00 +-1.2225552063150480e-01 +-2.5949838515881063e+00 +1.3667641276072011e+00 +-1.2183010231286862e-01 +-2.5989702550945104e+00 +4.7746956081103009e-01 +-9.7631649942704943e-02 +-2.6621232181982259e+00 +1.3964187033420166e+00 +-1.1247201493482058e-01 +-2.5905326112758944e+00 +1.3896687426545160e+00 +-1.1212080081120625e-01 +-2.6016773767170709e+00 +1.3987182655121060e+00 +-1.0401389752046143e-01 +-2.5943418252314068e+00 +1.3905231421245217e+00 +-1.0400214735021926e-01 +-2.6008626319159354e+00 +8.5440079359171328e-01 +-1.0484370009808093e-01 +-3.0123584312775540e+00 +4.8500373526277518e-01 +-9.0109765577076728e-02 +-2.6677290672785481e+00 +4.8500373526277518e-01 +-9.0109765577076728e-02 +-2.6677290672785481e+00 +1.2852948466108585e+00 +-9.6249633835283482e-02 +-2.4126169121900656e+00 +5.1353280214069785e-01 +-8.7681414939407828e-02 +-2.6804023359821056e+00 +5.1353280214069785e-01 +-8.7681414939407828e-02 +-2.6804023359821056e+00 +1.3922043746134043e+00 +-9.9478757512636434e-02 +-2.5952488688117228e+00 +9.2761432791410225e-01 +-1.0450244128759387e-01 +-3.0880531501448800e+00 +1.0706585985222603e+00 +-1.0651707750618124e-01 +-3.2606472235570170e+00 +1.0218583131607142e+00 +-1.0364870750831451e-01 +-3.2017572494172888e+00 +1.3971163146607306e+00 +-9.4428663723288883e-02 +-2.5913829375032775e+00 +1.3891946990531385e+00 +-9.4535926785180580e-02 +-2.5999106563022840e+00 +1.3987258898284749e+00 +-9.0358722510836750e-02 +-2.6015279268471052e+00 +1.0704705427380179e+00 +-9.6196588707523664e-02 +-3.2607379423460925e+00 +5.6291860888118439e-01 +-7.7594482230122636e-02 +-2.7031447113013263e+00 +1.3714596675738111e+00 +-8.5886769657311859e-02 +-2.6051281687587093e+00 +1.3975029910442465e+00 +-8.5300896828332196e-02 +-2.5909075671898707e+00 +1.3903634386144585e+00 +-8.5417614474677800e-02 +-2.6003351469272302e+00 +8.5482989998066106e-01 +-8.4643660856121711e-02 +-3.0141719978965327e+00 +1.2930681216111803e+00 +-7.8786006245145201e-02 +-2.4217375467924045e+00 +1.3231072599032723e+00 +-7.9557887390045032e-02 +-2.4388392516571420e+00 +5.7161870627373190e-01 +-5.9908081250914992e-02 +-1.8990770977714233e+00 +9.3577888132493880e-01 +-8.4607488258880245e-02 +-3.0917744758562917e+00 +9.3577888132493880e-01 +-8.4607488258880245e-02 +-3.0917744758562917e+00 +1.3623570792616977e+00 +-8.0249286836325179e-02 +-2.5978079664652900e+00 +1.3623570792616977e+00 +-8.0249286836325179e-02 +-2.5978079664652900e+00 +1.0685479905529733e+00 +-8.6157929665357860e-02 +-3.2574175972624526e+00 +1.0685479905529733e+00 +-8.6157929665357860e-02 +-3.2574175972624526e+00 +9.2892450488452460e-01 +-7.9696954197718772e-02 +-3.0929685918847336e+00 +9.2892450488452460e-01 +-7.9696954197718772e-02 +-3.0929685918847336e+00 +9.0796560334602749e-01 +-7.8008883870218995e-02 +-3.0811650268150204e+00 +1.3927777912857502e+00 +-7.4787627723831851e-02 +-2.6041672729361864e+00 +1.0589508130775140e+00 +-7.6266100199021733e-02 +-3.2460226087432398e+00 +8.0267488756841454e-01 +-7.1126460400831690e-02 +-2.9463160466293434e+00 +1.3244163873936758e+00 +-6.8975047314681279e-02 +-2.4556681566692977e+00 +1.0338850751294757e+00 +-7.4559961322151355e-02 +-3.2204503806318856e+00 +1.3212700300312263e+00 +-6.8341073274126279e-02 +-2.4361979871558517e+00 +5.6093049472997336e-01 +-5.7116143436867051e-02 +-2.7051335233938167e+00 +1.4556366452408935e+00 +-5.9572315685670126e-02 +-2.2162575896002221e+00 +1.3325033752965127e+00 +-5.9725396562438304e-02 +-2.5010312518868316e+00 +6.1380987287819877e-01 +-5.6319930607487780e-02 +-2.7494001077046168e+00 +5.3837630178108375e-01 +-4.3968915011632040e-02 +-2.6796193036013518e+00 +5.9313086366386836e-01 +-3.7362301464278949e-02 +-2.7425845035679979e+00 +5.6955142897993738e-01 +-3.6505890778790691e-02 +-2.7224262384132021e+00 +1.3029686043898485e+00 +-3.4004432075956617e-02 +-2.4296285948910854e+00 +4.0120205355980870e-01 +-3.1546633743163570e-02 +-2.6429783841867525e+00 +4.0119088390749608e-01 +-3.1368671701622761e-02 +-2.6429051657084686e+00 +4.4882766505051797e-01 +-2.8493300944148290e-02 +-2.6445874593145344e+00 +4.3628179733660372e-01 +-2.8333364963789461e-02 +-2.6441323666278591e+00 +4.3634362548258565e-01 +-2.8601213615244203e-02 +-2.6446075451965356e+00 +1.3244490673599434e+00 +-2.7461978609270889e-02 +-2.4326084595810857e+00 +1.3191322715161071e+00 +-2.7424069390860402e-02 +-2.4275888564808836e+00 +1.3339251420393330e+00 +-2.6167273742199643e-02 +-2.3623213236566887e+00 +1.3820142149301335e+00 +-1.8624089219154472e-02 +-2.5658285239353935e+00 +1.4004438269331712e+00 +-1.4261552320559253e-02 +-2.5958972623599812e+00 +1.4376085087356394e+00 +-1.5839424540485664e-02 +-2.2465637441045589e+00 +1.3239419569504600e+00 +-1.2813585529267483e-02 +-2.4599247894059513e+00 +1.3320180476768682e+00 +-1.0465179604727823e-02 +-2.3916562820752687e+00 +1.3993357145516960e+00 +-7.1754972025967357e-03 +-2.5946488801175467e+00 +1.4069094036312400e+00 +3.8497848159292435e-02 +-3.7336402386063416e+00 +8.6398619242263475e-01 +2.1657404494771271e-02 +-3.0200040044227219e+00 +1.2654848689267826e+00 +4.7356704056665019e-02 +-3.5285514666656943e+00 +1.9974798025584473e+00 +6.8773376840947170e-02 +-3.5905743590792207e+00 +9.9472644348392301e+00 +7.1990411352078543e-01 +-1.5449329582834483e+01 +1.3926476182015923e+00 +5.7619158133961255e-02 +-2.5958135268212263e+00 +3.9047708518648840e+00 +3.5910566273619005e-01 +-7.8536170227244426e+00 +7.7985937891657864e-01 +6.5468844317742331e-02 +-2.9250199437817748e+00 +1.0693657787345712e+00 +9.4160549342524172e-02 +-3.2601776704053749e+00 +6.3861545585992496e-01 +6.2063074499214013e-02 +-2.7858879306757345e+00 +1.3578869886693257e+00 +6.9178948270121568e-02 +-2.5268505478325398e+00 +1.3578869886693257e+00 +6.9178948270121568e-02 +-2.5268505478325398e+00 +1.5527472870320915e+00 +1.5438308421413485e-01 +-3.9610663170663507e+00 +1.0000825872186132e+00 +1.0317282070915673e-01 +-3.2058054979877548e+00 +1.4493094711304801e+00 +6.7658663856752496e-02 +-2.2396545586570578e+00 +1.4503167036207743e+00 +6.7718239590621274e-02 +-2.2404744041969278e+00 +9.4575205845048804e-01 +1.0577487083537174e-01 +-3.1370616319860618e+00 +6.2047285066081637e-01 +7.8416455661765166e-02 +-2.7678552874940072e+00 +1.4028640617145043e+00 +7.4101614969692753e-02 +-2.2766264686577293e+00 +8.2428285952429770e-01 +1.1225385906212970e-01 +-2.9651639554874092e+00 +1.3907828531431119e+00 +1.1632554623196341e-01 +-2.5946568982070870e+00 +1.3344852278161001e+00 +1.0347428353829061e-01 +-2.4087911986791024e+00 +9.6044256541624629e-01 +1.4345058399853824e-01 +-3.1443139482088940e+00 +4.5650732073653799e-01 +1.0586182262185544e-01 +-2.6568887296146033e+00 +2.3215909397200227e+00 +2.9473754954762282e-01 +-4.0465013834362296e+00 +1.3872924547138725e+00 +1.4486464863038725e-01 +-2.5815784457069353e+00 +1.3278083744275169e+00 +1.2861272691991990e-01 +-2.3846924839739363e+00 +1.3911530520564388e+00 +1.6110828808881225e-01 +-2.5947817794726782e+00 +1.3911530520564388e+00 +1.6110828808881225e-01 +-2.5947817794726782e+00 +1.3240380782894503e+00 +1.4798153211473894e-01 +-2.4522919453624077e+00 +1.3756622975483388e+00 +1.4983669798441471e-01 +-2.3047863199546490e+00 +1.3723437529678819e+00 +1.8008872788109437e-01 +-2.6004884763997187e+00 +7.9287138631930898e-01 +1.9640150597554534e-01 +-2.9404433522940852e+00 +3.9943261894287074e-01 +1.4664938966820504e-01 +-2.6581781815022922e+00 +7.9982291008591111e-01 +2.0227835292377264e-01 +-2.9450171900854931e+00 +3.6754157625461498e-01 +1.5004053409237406e-01 +-2.6483323143224329e+00 +3.6856677169541974e-01 +1.6063119822387673e-01 +-2.6516158650616872e+00 +5.6275215736149353e-01 +1.8049240585113283e-01 +-2.7191073342564325e+00 +1.3195863676318718e+00 +1.9891398384778528e-01 +-2.4358377256051642e+00 +1.4493868527740339e+00 +1.8699089142130668e-01 +-2.2443857510904546e+00 +4.2849101509289061e-01 +1.8115119958580722e-01 +-2.6585696401958239e+00 +1.4464291798337148e+00 +1.9788006305906664e-01 +-2.2375975055496515e+00 +3.6262558669138334e-01 +1.7786829942646157e-01 +-2.6531535936095358e+00 +7.6974323656631416e-01 +2.3716746125139673e-01 +-2.9222776441592186e+00 +4.0741645547664318e-01 +1.8164127412951125e-01 +-2.6555453339636736e+00 +7.3720918709650574e-01 +2.3925256424142133e-01 +-2.8923303043581976e+00 +1.3268137014350698e+00 +2.1840139644604317e-01 +-2.3859804919890260e+00 +1.3672717029920234e+00 +2.2205493212257410e-01 +-2.3218313430478101e+00 +6.8998245424713356e-01 +2.4064643130867838e-01 +-2.8412379482382741e+00 +7.8482787859502656e-01 +2.6104102471263158e-01 +-2.9349107877196126e+00 +1.3417083301113781e+00 +2.4440847290707998e-01 +-2.4974752282684523e+00 +1.3312425014443350e+00 +2.3979719917705655e-01 +-2.4635173487953188e+00 +1.3272810168043099e+00 +2.3406127308255090e-01 +-2.3929862417183276e+00 +1.3254604705035931e+00 +2.4018044498964577e-01 +-2.4301053140866449e+00 +9.7611164458271493e-01 +3.1181277190478079e-01 +-3.1497552733045979e+00 +7.9270263806445318e-01 +2.7215352528682907e-01 +-2.9440089411586419e+00 +7.7006056057721439e-01 +2.7803637379230089e-01 +-2.9263047912860563e+00 +9.2914314477651283e-01 +3.1926121625040571e-01 +-3.0966424365214613e+00 +9.2914314477651283e-01 +3.1926121625040571e-01 +-3.0966424365214613e+00 +1.3943003866922747e+00 +2.5224567867019515e-01 +-2.2931933284964794e+00 +6.4685665287034433e-01 +2.7114614682346377e-01 +-2.7948711503992238e+00 +1.4564157352364728e+00 +2.5842537018871875e-01 +-2.2475910431784984e+00 +1.3278235048223466e+00 +2.7875776460094565e-01 +-2.4498460790148000e+00 +6.9025943011296831e-01 +2.8844446482284830e-01 +-2.8467408651230559e+00 +9.6671133095067519e-01 +3.6095098672354192e-01 +-3.1516013661460249e+00 +3.0420747909032564e-01 +2.4562733501737927e-01 +-2.6684520971412082e+00 +1.4623140014838785e+00 +2.7770601602036499e-01 +-2.2295796256121121e+00 +8.5479489951932297e-01 +4.1402328371615349e-01 +-3.1679831717989497e+00 +8.5430675208562068e-01 +4.1371845153139036e-01 +-3.1667223702560796e+00 +1.7894716060509459e+00 +5.1440874112740675e-01 +-3.1356905005712989e+00 +1.7865566080379804e+00 +5.1614543037711202e-01 +-3.1195141032882541e+00 +1.8516304508523280e+00 +5.1050612870463696e-01 +-3.0458274663235394e+00 +1.8897600440645190e+00 +5.1644700018302570e-01 +-3.0252901000429868e+00 +1.8897600440645190e+00 +5.1644700018302570e-01 +-3.0252901000429868e+00 +1.8344558003527989e+00 +5.3429834562104139e-01 +-3.0631101913700531e+00 +5.3976799240905049e-01 +3.3869915617286239e-01 +-2.6968966095568923e+00 +4.1265424505680459e-01 +3.2718432267217173e-01 +-2.6513700628871835e+00 +4.2752294853948236e-01 +3.3305108811998962e-01 +-2.6553585168641134e+00 +3.9513127372876256e-01 +3.4098112268328623e-01 +-2.6571800363621594e+00 +3.4952711414441928e-01 +3.5005861542483868e-01 +-2.6584735905672661e+00 +5.2458290668194230e-01 +3.7422658261011660e-01 +-2.6798907991926271e+00 +3.4884198739501077e-01 +3.6255984698753324e-01 +-2.6577916636093488e+00 +4.1037137069521168e-01 +3.7660370573239105e-01 +-2.6480207309551957e+00 +4.2344023127717090e-01 +3.7948890389535472e-01 +-2.6481961304506765e+00 +3.2213997503373620e-01 +3.7409846490635795e-01 +-2.6593217502831825e+00 +3.6930546405097098e-01 +3.8027798951631137e-01 +-2.6477254451147472e+00 +3.5600790185455417e-01 +3.8031296295211797e-01 +-2.6481263055064121e+00 +3.4962725813099116e-01 +3.8057748741207720e-01 +-2.6496978771571946e+00 +3.0792857955879482e-01 +3.8104389634867486e-01 +-2.6600442645578259e+00 +4.0522067638184678e-01 +-1.5687951766149769e-01 +-2.6492322135981041e+00 +8.0505883460756811e-01 +-1.7793496304618875e-01 +-2.9474404659170959e+00 +5.6844187705341898e-01 +-1.0769063202710535e-01 +-1.9004392202322471e+00 +5.7106649874327975e-01 +-1.0598245623195110e-01 +-1.9050509514790495e+00 +5.1072299839172874e-01 +-1.4399671257494123e-01 +-2.6537389031992253e+00 +5.4141234064877020e-01 +-1.4407894312089511e-01 +-2.6726878265475542e+00 +5.7278753734447418e-01 +-9.8631709320241193e-02 +-1.8953736062161670e+00 +8.0279286644165104e-01 +-1.5812392585044546e-01 +-2.9413768034855625e+00 +1.3151717542255466e+00 +-1.2622048407749681e-01 +-2.4158406583537007e+00 +1.4001003041609803e+00 +-1.3147402730105226e-01 +-2.6030264244919579e+00 +5.5506326066407008e-01 +-9.5856761914861102e-02 +-2.7003499760978582e+00 +5.0255090761953169e-01 +-9.4841017084062215e-02 +-2.6769927827042310e+00 +4.9559086130343344e-01 +-9.4603878169737435e-02 +-2.6727589981207411e+00 +4.8050292875645162e-01 +-9.4203847039786806e-02 +-2.6646874823086759e+00 +4.8826630242898322e-01 +-9.3621802852168298e-02 +-2.6702874912334185e+00 +5.4594154079721324e-01 +-9.3367803825374560e-02 +-2.6863298507064570e+00 +4.9850242786574805e-01 +-9.1699766892873139e-02 +-2.6755639506913389e+00 +4.9159111022661661e-01 +-9.1371999137647944e-02 +-2.6682029487705066e+00 +4.9236008351828525e-01 +-9.1457334426864170e-02 +-2.6718124769781273e+00 +6.3565880995094959e-01 +-8.9112261173654561e-02 +-2.7723551343621464e+00 +8.2338802060997651e-01 +-9.3957143605922000e-02 +-2.9755398129745956e+00 +9.2163105775944543e-01 +-8.3479093325068060e-02 +-3.0882013228334020e+00 +1.0244970264762858e+00 +-8.3730563585814044e-02 +-3.2077090431489479e+00 +5.6632639691292019e-01 +-5.7705184911131004e-02 +-1.9021503637624364e+00 +1.3280429152479549e+00 +-7.4079489412377714e-02 +-2.4299584719805458e+00 +1.3211832857751664e+00 +-7.3850143572984972e-02 +-2.4721529296259832e+00 +1.3221967812808124e+00 +-7.1718836254723986e-02 +-2.4187173791599528e+00 +1.0806026961814066e+00 +-8.0185582847833933e-02 +-3.2683895273863022e+00 +1.3809624629653710e+00 +-7.3562643290328883e-02 +-2.5710895519067041e+00 +1.3408109196802498e+00 +-7.1457964113063890e-02 +-2.5108372302413056e+00 +1.3213499869026879e+00 +-6.9718378039695425e-02 +-2.4691928539969816e+00 +5.7661231590523265e-01 +-5.1339620300442042e-02 +-1.8903614691842787e+00 +5.9034176523226034e-01 +-5.9551587196614318e-02 +-2.7496525452397211e+00 +7.9560724095527668e-01 +-5.9435058300710823e-02 +-2.9366392108517032e+00 +5.8225675693846757e-01 +-4.9215636759161220e-02 +-1.8918701127605098e+00 +5.7962788543259391e-01 +-4.9331990259873650e-02 +-1.8920715519721651e+00 +5.7257074969134902e-01 +-4.9051505503531427e-02 +-1.8889082236859680e+00 +5.6547621434233031e-01 +-4.9099387969582367e-02 +-1.8956271760533776e+00 +1.6260377883180919e+00 +-7.0042770120305867e-02 +-4.0024450105461016e+00 +6.9429629048996322e-01 +-5.0149533567294020e-02 +-2.8226472446565580e+00 +6.4323306955243675e-01 +-4.4072971685377479e-02 +-2.7900775849375603e+00 +5.8966559052316403e-01 +-4.1094505065293913e-02 +-2.7427161058978355e+00 +3.6576173079110257e+00 +-5.1750944534618711e-02 +-7.5013326344980067e+00 +1.5161850068557405e+00 +-4.1003756142637668e-02 +-3.8630150745474330e+00 +1.3571067362446070e+00 +-4.1415578574506784e-02 +-2.3012092128495554e+00 +1.4207035718044110e+00 +-3.9858448610235943e-02 +-3.7411772627955528e+00 +6.0856235707544282e-01 +-3.8287020990049818e-02 +-2.7576824805853715e+00 +1.4424477496685491e+00 +-4.1062849146954045e-02 +-2.2285211996389851e+00 +1.3957553619404435e+00 +-3.9306234002592248e-02 +-2.5979893259182911e+00 +1.3272387223236140e+00 +-3.7779565715604903e-02 +-2.3285766727695116e+00 +1.3322807501049192e+00 +-3.7287547838267418e-02 +-2.5093702378111611e+00 +3.9929979299404594e-01 +-3.5243446549189886e-02 +-2.6453485405693900e+00 +4.5600330723773141e-01 +-2.9234579916681113e-02 +-2.6464533833843249e+00 +1.3752776413308199e+00 +4.7201270997801617e-03 +-3.6936736980312759e+00 +1.6157329875368345e+00 +1.3737989305003957e-02 +-3.9997393621613848e+00 +1.3935556971227065e+00 +1.2448100120970642e-02 +-3.7255753778462326e+00 +1.9325913775282846e+00 +1.2840248648294510e-02 +-3.4966233476222670e+00 +9.8979946949902615e+00 +4.1503114928087592e-01 +-1.5348456952253597e+01 +8.3851449278495682e-01 +1.8216172630929086e-02 +-2.9842967515243970e+00 +1.5137848090903305e+00 +5.0227839471207458e-02 +-3.8621135716230186e+00 +8.2565780541296985e-01 +1.8946386632432980e-02 +-2.9718682159160399e+00 +1.3245460046285693e+00 +1.2558638749329044e-02 +-2.4620355591814298e+00 +1.3240166721115563e+00 +1.5612336177483633e-02 +-2.3943411884975383e+00 +1.0716055516489167e+00 +3.9218108142648971e-02 +-3.2648879630608332e+00 +9.7541478982915664e-01 +3.4062600756958543e-02 +-3.1509383844800096e+00 +7.2323457635512522e-01 +3.0299625082352132e-02 +-2.8859324730050542e+00 +8.6560353435511406e-01 +4.3152184572484986e-02 +-3.0234017317239354e+00 +1.5546793642006709e+00 +5.2622350624415504e-02 +-2.9005911036346945e+00 +1.4034180020621279e+00 +4.1250126499744411e-02 +-2.6589004182494120e+00 +8.5313717363517860e-01 +4.5424332754729083e-02 +-3.0058783885263036e+00 +8.5313717363517860e-01 +4.5424332754729083e-02 +-3.0058783885263036e+00 +3.8531274424801065e+00 +2.6939998884041105e-01 +-7.8135780678209219e+00 +5.9220627192578867e-01 +3.3205812165135920e-02 +-2.7438374746707570e+00 +1.5011968015342800e+00 +5.5122374019371298e-02 +-2.8205976230394061e+00 +1.0018096858320460e+01 +6.8004968340990379e-01 +-1.5528534947931121e+01 +5.6816399064807832e-01 +3.3984463253686988e-02 +-2.7218124480770194e+00 +1.8683856693843599e+00 +8.5984914461363998e-02 +-3.3947588725355704e+00 +9.6860005687877830e+00 +6.8585719116955834e-01 +-1.5409172726315919e+01 +5.5644600650145115e-01 +3.5576488552192038e-02 +-2.7089341597734768e+00 +6.0406875572262431e-01 +4.4325701295527431e-02 +-2.7567707048701986e+00 +1.9026664689708099e+00 +1.0020336746297588e-01 +-3.4481716563521565e+00 +1.3939502092928207e+00 +6.1343998036440438e-02 +-2.5907415181902689e+00 +1.8702217836649933e+00 +1.0914086425081145e-01 +-3.3954790529441530e+00 +5.3166243080655917e-01 +4.8201795320607831e-02 +-2.6913823900210039e+00 +1.3434973345249368e+00 +5.8801700627196689e-02 +-2.4966840873871834e+00 +5.2538956749473309e-01 +4.8941840416209005e-02 +-2.6875212064121516e+00 +9.9285008008217250e+00 +8.5067538485656646e-01 +-1.5503576999351877e+01 +1.8731003815126122e+00 +1.1599892660344335e-01 +-3.3879416250014480e+00 +1.4206258619933776e+00 +5.7538757608651472e-02 +-2.2605763026721051e+00 +1.3323850638073382e+00 +1.2578272029640358e-01 +-3.6306460945667438e+00 +1.3319163444913358e+00 +7.1193373667122667e-02 +-2.4799252182201332e+00 +1.0153726832858569e+00 +1.0833683670181753e-01 +-3.2052150810944298e+00 +8.3775272132281453e-01 +1.0182798617449255e-01 +-2.9890674053837611e+00 +4.3969535081663563e-01 +7.2709088740189554e-02 +-2.6420100915977796e+00 +3.4495318289996280e-01 +8.0714808495033097e-02 +-2.6496308572701861e+00 +7.3282158144016440e-01 +1.1110034960164791e-01 +-2.8789657414003123e+00 +1.8332212534819718e+00 +2.6125935271237771e-01 +-4.4734139889124611e+00 +1.3923274597920530e+00 +1.2126799668597832e-01 +-2.6021830738368892e+00 +4.4377504584333899e-01 +9.0936695908719570e-02 +-2.6479009322189051e+00 +1.3278595764880927e+00 +1.1276228769368504e-01 +-2.3832529164935967e+00 +1.3392387167697488e+00 +1.2208784391891662e-01 +-2.4793731604321492e+00 +1.8642375114881369e+00 +2.9061652237562546e-01 +-4.3860621531800064e+00 +4.4409742370703037e-01 +1.0168526840368493e-01 +-2.6453338987736550e+00 +1.8403699324052978e+00 +3.0513867005074063e-01 +-4.4983269241058110e+00 +1.3339133644539094e+00 +1.2592362722214659e-01 +-2.4167405313809120e+00 +1.0289884612109788e+00 +1.8874866219950345e-01 +-3.2217393536741845e+00 +1.3958042000978577e+00 +1.5877359757255988e-01 +-2.5918827576046164e+00 +1.3221759410959302e+00 +1.4694914469485792e-01 +-2.4431509681026826e+00 +1.3267288627118523e+00 +1.4872350038660859e-01 +-2.3823479769145703e+00 +8.3576623967346997e-01 +1.8509473767280363e-01 +-2.9870200087585270e+00 +1.3733747327791876e+00 +1.5498938022424019e-01 +-2.3038974761299977e+00 +7.2127744906189628e-01 +1.8303927449475249e-01 +-2.8887999376850018e+00 +8.0520105107037210e-01 +1.9667377024513349e-01 +-2.9543075587130723e+00 +1.8318238140349361e+00 +4.1595704626865060e-01 +-4.5605892485709090e+00 +1.4471452539235741e+00 +1.6245566367556707e-01 +-2.2451701408101825e+00 +3.5703113460994973e-01 +1.4749287172526299e-01 +-2.6506667334408185e+00 +4.0022207916428360e-01 +1.5054161957871701e-01 +-2.6547617124209499e+00 +7.9239697006949128e-01 +2.0673723569575694e-01 +-2.9418100214506819e+00 +1.3892428922587450e+00 +2.0827745858442284e-01 +-2.6004688271402632e+00 +4.7129294269743782e-01 +1.6214480630652078e-01 +-2.6688643534985359e+00 +1.3947280651117417e+00 +2.0881576940163724e-01 +-2.5930998682671538e+00 +6.1815776869054628e-01 +1.8441295175969721e-01 +-2.7757251333337267e+00 +4.1320442625715981e-01 +1.5984848080398442e-01 +-2.6533746256447039e+00 +7.8471796244877812e-01 +2.1259605313512842e-01 +-2.9334172031867936e+00 +1.3887787981419712e+00 +2.1631240318102027e-01 +-2.6001669462247921e+00 +1.3961167806269159e+00 +2.1676286180464283e-01 +-2.5940128245478173e+00 +7.1526374516299596e-01 +2.0944209775852174e-01 +-2.8866399193531458e+00 +3.0722787478048014e-01 +1.6451658471792871e-01 +-2.6591571483422176e+00 +9.4060362965893374e-01 +2.5818171807298668e-01 +-3.1211459105322392e+00 +8.7690604001082539e-01 +2.4609665594750696e-01 +-3.0458352409343012e+00 +1.3450599025345080e+00 +2.2047360582797260e-01 +-2.5020408042064002e+00 +9.5799964227836087e-01 +2.7383572455781102e-01 +-3.1414100878191249e+00 +9.5805350355371866e-01 +2.7376106549161400e-01 +-3.1415472326390015e+00 +3.7384762345440264e-01 +1.7749667344852652e-01 +-2.6430365949997059e+00 +3.7384762345440264e-01 +1.7749667344852652e-01 +-2.6430365949997059e+00 +4.1614829313603147e-01 +1.8386747005575416e-01 +-2.6561639820630609e+00 +3.0367462736687900e-01 +1.8329444563527519e-01 +-2.6699402310149507e+00 +1.7250827369309394e+00 +3.3810513397653530e-01 +-3.1261363495747001e+00 +8.4709779769964499e-01 +2.7096441881760741e-01 +-2.9890555040450839e+00 +1.3541684826533797e+00 +2.5217518624391089e-01 +-2.5167414351697457e+00 +1.3838198172584737e+00 +2.6501991036356914e-01 +-2.5943604566628307e+00 +1.3829751294113111e+00 +2.6475964399727397e-01 +-2.5933566769966947e+00 +1.3807806945628818e+00 +2.6912486832736193e-01 +-2.6210907927425660e+00 +1.3251618982627449e+00 +2.4779735470163572e-01 +-2.4558075619268629e+00 +1.3936215760011530e+00 +2.9174842831284303e-01 +-2.5920527180198421e+00 +5.9469612234950509e-01 +2.5796122573646613e-01 +-2.7565346321570292e+00 +1.3269108553743179e+00 +2.7884057867627871e-01 +-2.3722884074537727e+00 +1.3810090421250212e+00 +2.7206374546801892e-01 +-2.2975368325434369e+00 +1.3812321085273613e+00 +2.7214835760235900e-01 +-2.2977402216454088e+00 +1.4421293421927825e+00 +2.7273327075798132e-01 +-2.2529077819712255e+00 +4.1790867337333665e-01 +2.5011950664186905e-01 +-2.6468468378755432e+00 +9.2827574590110917e-01 +3.6987058915167820e-01 +-3.1117903956643325e+00 +3.6002990600803625e-01 +2.5139927602540602e-01 +-2.6503514177114313e+00 +4.1176598100555756e-01 +2.5552299879341284e-01 +-2.6475687549250102e+00 +3.8069045757463127e-01 +2.5440981216906267e-01 +-2.6491865558226766e+00 +1.4419994739745079e+00 +2.8947412842844145e-01 +-2.2628304273216879e+00 +4.8517126402486110e-01 +2.7572840126519282e-01 +-2.6658610521687387e+00 +8.4163149793477077e-01 +4.1543850747977090e-01 +-3.1796730622479843e+00 +1.7743964801854324e+00 +5.0309183502712695e-01 +-3.1249425696752664e+00 +4.5009979105810560e-01 +2.9783496748624078e-01 +-2.6581627300777368e+00 +2.3812727331441339e+00 +6.1365452984830271e-01 +-3.3043807424217135e+00 +5.5130368590206325e-01 +3.3117389437278694e-01 +-2.7080620834596805e+00 +4.2400459379766792e-01 +3.2141842268961746e-01 +-2.6556703706128388e+00 +4.2174803238803249e-01 +3.2704324876333446e-01 +-2.6603250613202762e+00 +4.5651600888517485e-01 +3.3655424814059492e-01 +-2.6715789446527216e+00 +4.4811005572720142e-01 +3.3368524207318540e-01 +-2.6557095384153859e+00 +5.8609678745088312e-01 +3.7044182769710116e-01 +-2.7292606353285791e+00 +4.0838681643332331e-01 +3.3597325059598815e-01 +-2.6528975055492565e+00 +3.7710513558809705e-01 +3.3384753017690127e-01 +-2.6518783871140683e+00 +4.1942434929125050e-01 +3.3969216204047381e-01 +-2.6530112462486564e+00 +4.1857579086544766e-01 +3.3886396718111395e-01 +-2.6495843394922733e+00 +5.7449921599227349e-01 +3.7382944586286404e-01 +-2.7268895740074095e+00 +3.8827916269761525e-01 +3.4128485071970066e-01 +-2.6587836968231948e+00 +4.4643892628676374e-01 +3.4793823041025790e-01 +-2.6619556612957540e+00 +4.5094484988048283e-01 +3.4956826151981057e-01 +-2.6620630387747646e+00 +3.2869492480298312e-01 +3.3563598094017383e-01 +-2.6532665334747469e+00 +3.6209328078635028e-01 +3.4676484386074907e-01 +-2.6557092255940118e+00 +4.1143177794139346e-01 +3.6248154168659924e-01 +-2.6563359802761721e+00 +4.9999982549765859e-01 +3.7656827439816198e-01 +-2.6716180462274939e+00 +3.0396440846960299e-01 +3.5937023484511377e-01 +-2.6677274118856187e+00 +3.0402831343449532e-01 +3.6293276972195154e-01 +-2.6657375592746457e+00 +3.2379588656289110e-01 +3.6575284003406483e-01 +-2.6579569818128714e+00 +4.7967030639624442e-01 +3.9272206429584705e-01 +-2.6711982414634230e+00 +3.1011771403273403e-01 +3.9772840730963588e-01 +-2.6692237170120778e+00 +3.1016997378973488e-01 +4.0303805313023860e-01 +-2.6698049696892157e+00 +4.8899469046575855e-01 +4.5197600182848097e-01 +-2.6752265792902770e+00 +2.9779347573476278e-01 +4.4903297606429554e-01 +-2.6671350188077954e+00 +4.0907647742165371e-01 +-1.5983254240420167e-01 +-2.6494798757522626e+00 +4.0907647742165371e-01 +-1.5983254240420167e-01 +-2.6494798757522626e+00 +4.1733109910558686e-01 +-1.5954325829612057e-01 +-2.6484866343479059e+00 +4.1733109910558686e-01 +-1.5954325829612057e-01 +-2.6484866343479059e+00 +4.0794029373056673e-01 +-1.5686104404798681e-01 +-2.6490406384635148e+00 +4.0058708252923381e-01 +-1.5658345393139378e-01 +-2.6477918030693144e+00 +4.1041986999819557e-01 +-1.5460705231754210e-01 +-2.6491928275827337e+00 +4.0287522758306787e-01 +-1.5426026607032117e-01 +-2.6480139475251656e+00 +3.9398402968895430e-01 +-1.5224413410162596e-01 +-2.6518136576994924e+00 +5.0531728183716940e-01 +-1.4349072155864914e-01 +-2.6508137753102656e+00 +5.0531728183716940e-01 +-1.4349072155864914e-01 +-2.6508137753102656e+00 +5.6944416986716184e-01 +-1.0407663530362822e-01 +-1.8978696137359732e+00 +8.2293017785669109e-01 +-1.6433628242058890e-01 +-2.9702484003076903e+00 +5.7004134903364612e-01 +-9.9435409057420251e-02 +-1.9014304735218910e+00 +5.7127623523524573e-01 +-9.7564882215988219e-02 +-1.8965080004620802e+00 +5.7245855713540195e-01 +-9.6793391249040905e-02 +-1.8954560233266426e+00 +5.8073626516250454e-01 +-9.5829376096065483e-02 +-1.8948088729084709e+00 +5.7009798364409314e-01 +-9.2466480582821239e-02 +-1.8943885336572552e+00 +5.8092963457351199e-01 +-9.2396513088320434e-02 +-1.8922597723144965e+00 +5.8408997846343513e-01 +-9.1238516420688476e-02 +-1.8952378983706841e+00 +5.7215328139732369e-01 +-8.3891802196179519e-02 +-1.8954272551361422e+00 +5.7424327788890550e-01 +-8.3188295866373427e-02 +-1.8952713485890860e+00 +1.0795578227509020e+00 +-1.4474999836905680e-01 +-3.2627644815852448e+00 +5.6903568346092470e-01 +-8.0661243746702041e-02 +-1.9049829764265891e+00 +7.8701207549563257e-01 +-1.2052866432278332e-01 +-2.9276238834659063e+00 +5.7008013760848231e-01 +-7.9845991260915045e-02 +-1.8982540830232422e+00 +4.9966301120045703e-01 +-1.0242578050362237e-01 +-2.6750401077704034e+00 +4.9966301120045703e-01 +-1.0242578050362237e-01 +-2.6750401077704034e+00 +4.8830518600713546e-01 +-1.0188321357933240e-01 +-2.6660676076471659e+00 +4.8830518600713546e-01 +-1.0188321357933240e-01 +-2.6660676076471659e+00 +4.8168168523755250e-01 +-1.0169431679824437e-01 +-2.6643167658274702e+00 +4.8168168523755250e-01 +-1.0169431679824437e-01 +-2.6643167658274702e+00 +1.3885320346631944e+00 +-1.1693444325773505e-01 +-2.5988584126984025e+00 +1.4013753392427160e+00 +-1.1707818811643307e-01 +-2.5999539655313582e+00 +7.8727608677369854e-01 +-1.1183261925301349e-01 +-2.9285117615082905e+00 +5.9664132512764001e-01 +-9.5718350060904997e-02 +-2.7354474138935894e+00 +5.8651986701878311e-01 +-9.4660438487442544e-02 +-2.7288990641477282e+00 +5.1354953225556765e-01 +-9.2301087601597637e-02 +-2.6824931944246173e+00 +3.3810003938228550e-01 +-8.6738242341412461e-02 +-2.6503867930953144e+00 +5.7938282389725304e-01 +-7.0072686776100304e-02 +-1.8921603696098652e+00 +4.6484379996134761e-01 +-8.5870045430122638e-02 +-2.6366976822991322e+00 +9.4454477848503626e-01 +-1.0430829038156730e-01 +-3.0981087335522863e+00 +5.7539809821291865e-01 +-6.4350514472517745e-02 +-1.8959033070002946e+00 +5.6877320325326564e-01 +-6.4506945044670513e-02 +-1.8968134569392658e+00 +1.4353794988009196e+00 +-9.7865689563854108e-02 +-3.9530392011471207e+00 +1.3275941843145052e+00 +-6.8131048080309869e-02 +-2.4320232124024193e+00 +9.3300580656112020e-01 +-6.9803089608232172e-02 +-3.0834521726920396e+00 +5.6797077689156006e-01 +-5.1634754458381588e-02 +-1.8963589212916390e+00 +5.6691821226966177e-01 +-5.1551441693552726e-02 +-1.8951171692345063e+00 +5.6374502257949211e-01 +-5.1641841762484736e-02 +-1.8996682075564080e+00 +5.8412996562055497e-01 +-5.1573128560363959e-02 +-1.8925101660036463e+00 +5.7306274418363945e-01 +-5.1359963494505341e-02 +-1.8918600502443481e+00 +5.7018153647966574e-01 +-5.1440046185549634e-02 +-1.8938858903411158e+00 +1.3311161985375246e+00 +-6.2072238645527890e-02 +-2.3407562269082929e+00 +1.3706749289541689e+00 +-4.3494011245839390e-02 +-2.5666572256860447e+00 +7.8781861862011338e-01 +-3.9489712813630978e-02 +-2.9294020899835949e+00 +1.2982282840230319e+00 +-3.8228938629451190e-02 +-2.4294224832545219e+00 +3.9228620701561817e-01 +-3.5687899231750059e-02 +-2.6463665651939792e+00 +4.1615506113993700e-01 +-3.3391063690515796e-02 +-2.6447480550268709e+00 +4.1673559655304127e-01 +-3.3346793804940489e-02 +-2.6459777078249833e+00 +1.4544104160773346e+00 +-3.4177384840483688e-02 +-2.2190710721302325e+00 +1.4419408714443738e+00 +-3.4033000261308524e-02 +-2.2277687507636883e+00 +1.4872709592869904e+00 +-1.4140015847637971e-02 +-3.8136400770489542e+00 +1.3891804633182914e+00 +-2.0243057050490693e-02 +-2.5975783639713321e+00 +1.4001176059686438e+00 +-1.9171601563144187e-02 +-2.5969793191074060e+00 +1.5859643196763933e+00 +4.8489989720962726e-03 +-3.9634691428044748e+00 +1.5871489971992205e+00 +5.2628459470187815e-03 +-3.9644681568009816e+00 +1.3336721899663448e+00 +-1.2128657237433600e-02 +-2.3966623360253081e+00 +1.0710658164477800e+00 +2.9757188709449195e-03 +-3.2634620047315011e+00 +1.9061976215508056e+00 +2.3997138389608635e-02 +-3.4552306541474551e+00 +9.9093731370211025e+00 +3.6295500832553768e-01 +-1.5416099069394708e+01 +1.3267400138396945e+00 +1.2210100689484396e-02 +-2.4192578484472387e+00 +9.3224656116864812e-01 +2.4823326390752902e-02 +-3.0995781564308569e+00 +8.1268293633306887e-01 +1.9632692714031515e-02 +-2.9561223712334121e+00 +8.2108064366056566e-01 +2.3361377454191583e-02 +-2.9698910525107101e+00 +1.5867216511590949e+00 +7.9044140180959385e-02 +-3.9627902611899288e+00 +1.4449493850437729e+00 +3.9009111594397419e-02 +-2.7234323010986290e+00 +3.9245808272910234e+00 +2.6207011653454010e-01 +-7.9149136260192456e+00 +9.6367294255690990e+00 +6.3420911650847056e-01 +-1.5381067451985427e+01 +1.5407226114395951e+00 +9.1716788977605226e-02 +-3.9217211310197722e+00 +8.0678991534345479e-01 +4.8479754519415434e-02 +-2.9501130502549953e+00 +1.5185759909052046e+00 +9.8652662115262982e-02 +-3.8915151088544402e+00 +1.3753332947900430e+00 +5.7625034868395868e-02 +-2.6168959020360560e+00 +9.8834812885384871e+00 +7.9581756810144100e-01 +-1.5446738060680216e+01 +1.3253310805549616e+00 +5.1765924594009027e-02 +-2.4171120311588696e+00 +1.3877302807000991e+00 +6.1472119822719586e-02 +-2.5967125099578126e+00 +1.3302333866876042e+00 +5.1349845908178239e-02 +-2.3843851056215084e+00 +7.2772974803613788e-01 +6.3671886726791971e-02 +-2.8902945328555436e+00 +1.3477016478916131e+00 +6.2027142214345708e-02 +-2.5068792362322281e+00 +3.7944113953964016e+00 +3.7585563589122839e-01 +-7.8416104079990312e+00 +1.3255305208327126e+00 +6.3449172211850924e-02 +-2.4570661324064447e+00 +8.4052617817388087e-01 +7.9247754260807560e-02 +-2.9906748914793293e+00 +1.3250593831372770e+00 +6.4338973798384935e-02 +-2.4331860843829274e+00 +1.3314664423849687e+00 +6.5674550963362069e-02 +-2.4337909883113866e+00 +1.0477926081679418e+00 +9.8726338650515388e-02 +-3.2308536557093861e+00 +7.9510785993419031e-01 +8.5206623893684177e-02 +-2.9309056864726348e+00 +1.3268261243180164e+00 +7.6721119870197668e-02 +-2.4667336850379034e+00 +3.7960596710751759e+00 +4.7024112464784634e-01 +-7.8447015258199047e+00 +4.2387049012437417e-01 +7.1299431096779595e-02 +-2.6421636919927192e+00 +1.3937884534036156e+00 +1.0258079839078672e-01 +-2.5900903433885971e+00 +5.0686142431762127e-01 +8.0591463890574380e-02 +-2.6848199094575622e+00 +4.8260248084974544e-01 +8.1103008170976737e-02 +-2.6635885236427264e+00 +1.3236126530016989e+00 +9.6648396513689019e-02 +-2.4284335686493721e+00 +6.4484330789116828e-01 +9.7264042801522940e-02 +-2.7882529354408687e+00 +1.3881683355295527e+00 +1.1136637509493946e-01 +-2.5970654877358013e+00 +1.8298418927580253e+00 +2.6041829036655062e-01 +-4.4210334753212566e+00 +1.8298418927580253e+00 +2.6041829036655062e-01 +-4.4210334753212566e+00 +7.2469419165458082e-01 +1.1571351626709804e-01 +-2.8880560846455898e+00 +1.3274904022215097e+00 +1.0713709084921563e-01 +-2.3829073453198446e+00 +2.9631413697080283e-01 +8.8789535599370834e-02 +-2.6671876547055100e+00 +1.8637273899874243e+00 +2.7561259166479984e-01 +-4.4120968337603550e+00 +6.1743727567450091e-01 +1.1169294775539777e-01 +-2.7745155493611184e+00 +1.4445993955398995e+00 +1.4258692825189453e-01 +-2.7236407244255183e+00 +1.8259473186740516e+00 +2.8933980550685401e-01 +-4.4720197383275568e+00 +1.3536476549423850e+00 +1.3031003503940605e-01 +-2.4972184955157668e+00 +1.8746861725392472e+00 +3.0257074031614190e-01 +-4.4439501598286677e+00 +1.8647679452629247e+00 +3.0140193627145628e-01 +-4.4233980640696355e+00 +1.3282162772732040e+00 +1.2216600418363951e-01 +-2.3835973736577851e+00 +1.8047610001430241e+00 +2.1735835398270340e-01 +-3.2636949253568339e+00 +1.8047610001430241e+00 +2.1735835398270340e-01 +-3.2636949253568339e+00 +1.3877053095712810e+00 +1.4556272622245944e-01 +-2.5729782516147486e+00 +5.9945814560388655e-01 +1.3825426276271996e-01 +-2.7534988575019868e+00 +5.1690062421766070e-01 +1.3097733545258081e-01 +-2.6834149749777882e+00 +8.8373562361699365e-01 +1.8184047229065028e-01 +-3.0537406532134210e+00 +9.0316449075472072e-01 +1.8611000065037106e-01 +-3.0810152176385475e+00 +1.0203878238952520e+00 +2.1153933902652555e-01 +-3.2177399445071813e+00 +1.3246894047840776e+00 +1.5647595909275111e-01 +-2.4151348782598778e+00 +1.8115057896187039e+00 +3.7158625073692397e-01 +-4.4458377953813439e+00 +1.3244069150873510e+00 +1.5952000817469175e-01 +-2.4134655445247946e+00 +8.4596754904318294e-01 +1.9104574980931538e-01 +-2.9973786278456935e+00 +1.3290886795998214e+00 +1.6022913214562690e-01 +-2.4064470215350720e+00 +1.3205830098434097e+00 +1.6237735955549676e-01 +-2.4321930895400365e+00 +1.3815407268504341e+00 +1.8150993445078056e-01 +-2.5832875444215304e+00 +1.3752677558679873e+00 +1.6191840898524787e-01 +-2.3001792297146091e+00 +1.3903780858061623e+00 +1.9370146097193189e-01 +-2.5891315177213978e+00 +1.3882717118636818e+00 +2.0040339901693888e-01 +-2.5985530430280437e+00 +1.8197348541607414e+00 +4.2877737261338045e-01 +-4.5513618753176530e+00 +4.8154917739458603e-01 +1.5794553425969962e-01 +-2.6625835223226271e+00 +4.8154917739458603e-01 +1.5794553425969962e-01 +-2.6625835223226271e+00 +1.3144343885008496e+00 +1.8466783271265255e-01 +-2.4560241856521237e+00 +1.8557427384796101e+00 +4.4032438576869787e-01 +-4.5927164280145192e+00 +8.0567201705059321e-01 +2.1268650407699327e-01 +-2.9544902200936445e+00 +1.3589659554210913e+00 +2.0525906395039570e-01 +-2.5272050900722123e+00 +4.1944019473041660e-01 +1.6363669402401060e-01 +-2.6524246515143264e+00 +1.3200782471602468e+00 +1.8740756223562630e-01 +-2.3715960148739033e+00 +1.3221382641699635e+00 +1.8760361910880230e-01 +-2.3633918086047467e+00 +1.4490534469028764e+00 +1.8341988925347230e-01 +-2.2387181989534963e+00 +1.3917042933806991e+00 +2.2431806534650162e-01 +-2.6034852292576685e+00 +7.7826285381889859e-01 +2.5375596094455044e-01 +-2.9241015284351999e+00 +6.4380480176166632e-01 +2.2900370126145733e-01 +-2.7950249680705630e+00 +8.4024390354183609e-01 +2.6752107131207981e-01 +-2.9836023555355213e+00 +1.3632944130768914e+00 +2.6123929784854028e-01 +-2.6037669866557978e+00 +6.3910094393358463e-01 +2.3969814793176050e-01 +-2.8027398068155631e+00 +7.4090034630423440e-01 +2.6792256680644372e-01 +-2.8902641874707338e+00 +9.7927269191918753e-01 +3.2107764255986121e-01 +-3.1426727296769421e+00 +7.5915036238077971e-01 +2.7565339565676694e-01 +-2.9190582690087319e+00 +9.6413864360895918e-01 +3.2435774267740075e-01 +-3.1416592432581085e+00 +7.0192924590175543e-01 +2.6659016150212722e-01 +-2.8519270683730462e+00 +6.0450885730216131e-01 +2.4680412894254375e-01 +-2.7622706063450972e+00 +6.6002483245289045e-01 +2.5705869493471956e-01 +-2.7960580924928458e+00 +1.7616257559736834e+00 +3.9844043090726228e-01 +-3.1114808667108322e+00 +1.3970431692108620e+00 +2.5772231591383815e-01 +-2.3020744151991162e+00 +5.8859799608960139e-01 +2.5903532690041958e-01 +-2.7528192212613862e+00 +1.3236332986980048e+00 +2.7780473869628913e-01 +-2.4306598089813556e+00 +5.3074977875520002e-01 +2.5421519324137032e-01 +-2.6952746602878039e+00 +5.3128525506517699e-01 +2.6029766281476152e-01 +-2.6986516301179506e+00 +1.3377159467896471e+00 +2.8328624691562942e-01 +-2.3556287274246115e+00 +3.8081276923675195e-01 +2.5815210907520525e-01 +-2.6472500603468299e+00 +3.3556946482140715e-01 +2.5854467222265048e-01 +-2.6541299811047896e+00 +2.9000655374034590e-01 +2.5906666802476674e-01 +-2.6717922682571071e+00 +1.7958963245001422e+00 +5.2430874029852659e-01 +-3.1249141509814748e+00 +5.3754177808044679e-01 +3.3739943647919185e-01 +-2.7049595424342239e+00 +4.2509023706364757e-01 +3.3436969231928060e-01 +-2.6549997908130591e+00 +3.3344750535351059e-01 +3.3809828257041874e-01 +-2.6507699103041800e+00 +3.2784558334978925e-01 +3.3836363311903184e-01 +-2.6524715059646407e+00 +4.4353292030539859e-01 +3.5916154024339703e-01 +-2.6605572744171893e+00 +4.5966295786358224e-01 +3.7506932455952358e-01 +-2.6583124270220559e+00 +4.3058478192165939e-01 +3.7609444112510043e-01 +-2.6516490729996693e+00 +4.3390447374151592e-01 +3.8424436444703713e-01 +-2.6517024246440468e+00 +3.5313593947548849e-01 +3.7724824189320588e-01 +-2.6509724643868147e+00 +4.6957538741427707e-01 +4.0217420960768790e-01 +-2.6714877454285189e+00 +4.6232747784191447e-01 +4.0450067265280476e-01 +-2.6701896660314151e+00 +3.1522768550280567e-01 +3.9751898023287902e-01 +-2.6688401959013874e+00 +3.1994762661202475e-01 +4.0252031801077975e-01 +-2.6679701687380244e+00 +3.1294268159889155e-01 +4.0551793676268894e-01 +-2.6689696703145280e+00 +4.9646942590099868e-01 +4.5366753354588413e-01 +-2.6745235033522419e+00 +5.0439055974264180e-01 +4.6043074264899581e-01 +-2.6796014970986000e+00 +3.4352525146712820e-01 +4.5949372294720492e-01 +-2.6955215198084548e+00 +2.9357700221458127e-01 +4.5154354703313954e-01 +-2.6683801167719574e+00 +3.7894420593689288e-01 +4.6695399121099374e-01 +-2.6479988492949706e+00 +4.1161875851028895e-01 +-1.5951434353922717e-01 +-2.6478470808387899e+00 +4.0046221804935539e-01 +-1.5933697650462650e-01 +-2.6485433718631071e+00 +4.0046221804935539e-01 +-1.5933697650462650e-01 +-2.6485433718631071e+00 +4.1408714014874137e-01 +-1.5937446608481184e-01 +-2.6474018584543266e+00 +4.1408714014874137e-01 +-1.5937446608481184e-01 +-2.6474018584543266e+00 +5.8096234051524787e-01 +-1.1493297548310970e-01 +-1.8905363541301474e+00 +4.1052523279472880e-01 +-1.5758046907299475e-01 +-2.6488595086554487e+00 +4.0744615609422841e-01 +-1.5393360382791335e-01 +-2.6487136058254666e+00 +4.7217432764555428e-01 +-1.4319798967244168e-01 +-2.6446868691543259e+00 +4.9810081404735096e-01 +-1.4504295336932527e-01 +-2.6703501631306108e+00 +5.7363392864103113e-01 +-1.0404171728265672e-01 +-1.8959732381395413e+00 +1.2334859499164208e+00 +-1.6897453028031245e-01 +-2.6862694152756199e+00 +5.7520641061076849e-01 +-1.0369980462095814e-01 +-1.8937455947996902e+00 +8.2993962247280451e-01 +-1.6460125189695665e-01 +-2.9774306768813479e+00 +8.2993962247280451e-01 +-1.6460125189695665e-01 +-2.9774306768813479e+00 +1.3902899697131483e+00 +-1.6092038710311748e-01 +-2.5997312563090182e+00 +1.3912588516937157e+00 +-1.5727717406084060e-01 +-2.6004553881626924e+00 +1.3771373222263052e+00 +-1.5093991273289736e-01 +-2.5815025494310055e+00 +5.7571430641093246e-01 +-9.5188557824869791e-02 +-1.8930705785649624e+00 +5.6969272661378523e-01 +-9.4046284895331664e-02 +-1.8939374430104987e+00 +5.7306079685987743e-01 +-9.3903898631407676e-02 +-1.8934718822811718e+00 +4.5137887777565838e-01 +-1.2229997031024860e-01 +-2.6098251671973505e+00 +5.6938149106555580e-01 +-8.3646491166791945e-02 +-1.9062284725718337e+00 +1.2713744870099641e+00 +-1.1410134093520391e-01 +-2.3539688174748647e+00 +1.3542417330134642e+00 +-1.1933233124692449e-01 +-2.5053821396573897e+00 +1.3550015240453808e+00 +-1.1947434595454218e-01 +-2.5059534087955133e+00 +1.3350429786494149e+00 +-1.1575421574047101e-01 +-2.4278337873310130e+00 +1.3773925280914350e+00 +-1.1925065395926429e-01 +-2.5820690509329989e+00 +6.0076771192783762e-01 +-9.7737652190159452e-02 +-2.7404552436202381e+00 +5.7646434025612481e-01 +-9.6585665777033106e-02 +-2.7166206416812368e+00 +4.7992078161363994e-01 +-9.1484548016434047e-02 +-2.6639814214498503e+00 +1.5654233255462193e+00 +-1.3610382257162404e-01 +-3.9236609743082158e+00 +5.6917173980330704e-01 +-6.6979466216687530e-02 +-1.8962774779094613e+00 +6.1701082976291743e-01 +-8.5192458935297227e-02 +-2.7515578629823674e+00 +5.7473551784482224e-01 +-6.5333079584213125e-02 +-1.8923003503016114e+00 +8.2423290656519532e-01 +-8.9966233682661559e-02 +-2.9692323058411807e+00 +5.7079793551277180e-01 +-6.4055822184499150e-02 +-1.8963510649706430e+00 +9.2805259681511687e-01 +-9.3194518467221321e-02 +-3.0939872549187033e+00 +5.2717294863691599e-01 +-7.4368231714701499e-02 +-2.6697422919119007e+00 +9.3282786177300381e-01 +-7.7620228819619053e-02 +-3.0953751801602882e+00 +5.8909885684760410e-01 +-5.3065048297621972e-02 +-1.8929459394104158e+00 +9.1966865109324503e-01 +-6.9304312023115530e-02 +-3.0862888909740853e+00 +1.3276363058263465e+00 +-6.4512914818313977e-02 +-2.4130280736305827e+00 +1.3271271402771452e+00 +-6.4905760790339162e-02 +-2.4299459665723471e+00 +1.6278682412905630e+00 +-8.1186791707537981e-02 +-4.0013067573423573e+00 +1.6236323381016271e+00 +-8.0982022673051976e-02 +-3.9943790643894777e+00 +5.8078537698817934e-01 +-5.1823058390865033e-02 +-1.8921912484930872e+00 +9.1680365872235536e-01 +-6.7268749181831733e-02 +-3.0893886207603027e+00 +1.3459932181023491e+00 +-6.1790450872924368e-02 +-2.3256834534695701e+00 +3.7507679789285846e+00 +-1.3026645949400942e-01 +-7.6033357674586259e+00 +1.5733762661836430e+00 +-7.0251773607211798e-02 +-3.9400174179349867e+00 +3.3659323948370590e-01 +-4.9051309762583643e-02 +-2.6408681868908204e+00 +1.5726062694486389e+00 +-6.1201059024560689e-02 +-3.9491832397802300e+00 +1.0678265081270850e+00 +-4.7469130708040347e-02 +-3.2572688669117600e+00 +1.3290831823947284e+00 +-4.2873791336807847e-02 +-2.3442370660066278e+00 +1.6165500539414921e+00 +-4.1549413123674730e-02 +-4.0000653882856323e+00 +4.5503480767449012e-01 +-3.2121892815935554e-02 +-2.6479145730596474e+00 +3.7522360333207633e-01 +-3.0710036716498319e-02 +-2.6403063596702703e+00 +6.1473751443108093e-01 +-2.9241764589117161e-02 +-2.7567814520867553e+00 +3.8340017107005160e+00 +2.6527003800246272e-03 +-7.7107746228763396e+00 +5.2688334298221262e-01 +-2.6899076232009482e-02 +-2.6726888932830031e+00 +4.5350443618481112e-01 +-2.6177067908828278e-02 +-2.6460193476682785e+00 +4.5350443618481112e-01 +-2.6177067908828278e-02 +-2.6460193476682785e+00 +1.3095626767463948e+00 +-2.5562594847479816e-02 +-2.4191006532363981e+00 +1.3228547716324615e+00 +-2.3734656433061552e-02 +-2.4259582343162136e+00 +4.4911581258195221e-01 +-2.2028038441341328e-02 +-2.6480311020220060e+00 +4.3583091588051659e-01 +-2.0126248958931319e-02 +-2.6409915304399258e+00 +4.3523426656670816e-01 +-2.0162395509670920e-02 +-2.6415052106863381e+00 +1.3385958333307117e+00 +-1.5946910961957505e-02 +-2.3553502455530078e+00 +1.3388648585789540e+00 +-1.5803548423038712e-02 +-2.3523245516165843e+00 +1.3412010052421084e+00 +-1.2256964381006451e-02 +-2.4116123540434415e+00 +1.0645658824720943e+00 +5.1803778066340494e-03 +-3.2567258921760351e+00 +1.7537406165684093e+00 +2.1871740308665292e-02 +-3.1890142528358041e+00 +9.8307656596689696e+00 +3.9102309327558465e-01 +-1.5431791049259488e+01 +2.8130022637756502e+00 +8.1461754363152061e-02 +-4.7784566010193750e+00 +9.4732895825675378e-01 +2.4546269909717706e-02 +-3.1200752980026931e+00 +8.0764078075580592e-01 +2.0670050737460578e-02 +-2.9540877965687939e+00 +1.1809737578940895e+00 +4.8814348077537227e-02 +-3.4116988815731770e+00 +1.8791637328870310e+00 +6.3364627706078855e-02 +-3.4233455674301516e+00 +1.0082079613312985e+01 +5.9545708676980091e-01 +-1.5579699772800407e+01 +7.1692442739246465e-01 +3.4258683147412490e-02 +-2.8762154173179604e+00 +3.8411824753327926e+00 +2.5763201145170161e-01 +-7.8216482482970795e+00 +9.9831309645641504e+00 +6.9539003144577927e-01 +-1.5539955205948438e+01 +1.9873962750127008e+00 +1.0769341701222548e-01 +-3.5756173438596166e+00 +9.7563813972894646e+00 +7.9580910702008023e-01 +-1.5472737466157412e+01 +3.8451467612746608e+00 +3.4341074291508289e-01 +-7.8313822147878112e+00 +3.8525200130139039e+00 +3.5284427843074473e-01 +-7.8263048257632839e+00 +3.8525200130139039e+00 +3.5284427843074473e-01 +-7.8263048257632839e+00 +9.7141556707369467e+00 +8.4878225471882218e-01 +-1.5424969094282142e+01 +6.4215290453920570e-01 +5.0036776945757665e-02 +-2.6239174276065320e+00 +1.3870885745698307e+00 +6.5511099573172610e-02 +-2.5974910529660504e+00 +1.4625066134314522e+00 +7.4830654583949607e-02 +-2.7483395620108002e+00 +1.4660621410242227e+00 +7.7915974948021785e-02 +-2.7571554785967090e+00 +1.3217498845656939e+00 +6.8185435197535407e-02 +-2.4576313504022389e+00 +9.3150980954481410e-01 +2.9588009020584720e-02 +-1.8637044805200524e+00 +1.3221859541493104e+00 +7.0004017301779631e-02 +-2.4195633739112830e+00 +1.3733522527389226e+00 +8.4687210599331153e-02 +-2.6136969029778383e+00 +1.3212912564074983e+00 +7.5478758269231463e-02 +-2.4182490209903627e+00 +1.3545402155083859e+00 +7.2938956370983105e-02 +-2.3281317742286554e+00 +1.3569608292370614e+00 +7.3185777962707699e-02 +-2.3265020071812152e+00 +5.8640495769116763e-01 +7.6860400931226008e-02 +-2.7485556506569089e+00 +1.3197141381341204e+00 +8.2623893771481244e-02 +-2.4001961028228691e+00 +1.3565390736418375e+00 +8.5177233328235777e-02 +-2.3167094316424883e+00 +1.8356027245606903e+00 +2.3297962630198085e-01 +-4.4388255273966539e+00 +1.3547558093556296e+00 +8.5753592086727573e-02 +-2.3202797429628430e+00 +3.5580271189094892e-01 +7.3129279969893005e-02 +-2.6421940501283361e+00 +1.3489956337962714e+00 +1.0010558282021451e-01 +-2.4900049326337794e+00 +1.3489956337962714e+00 +1.0010558282021451e-01 +-2.4900049326337794e+00 +7.9071386784873243e-01 +1.1346350853963653e-01 +-2.9351269164249749e+00 +1.8546027468632169e+00 +2.5330118143728053e-01 +-4.3890629343405134e+00 +4.4061980334731382e-01 +9.1263824692561626e-02 +-2.6500224065350686e+00 +6.8005641514993942e-01 +1.2049148992522456e-01 +-2.8428330690777810e+00 +1.3311241997372383e+00 +1.1480332018904690e-01 +-2.4108090507407600e+00 +1.7736182065864778e+00 +2.8590865001886917e-01 +-4.4831618109545692e+00 +7.8653874915245703e-01 +1.3781406163080934e-01 +-2.9320638497267941e+00 +1.8552907714486639e+00 +3.0091658315090836e-01 +-4.4234073916294507e+00 +1.3993465203518274e+00 +1.4581630357481912e-01 +-2.6555617850236235e+00 +9.6647279963225197e-01 +1.6581891101417121e-01 +-3.1533509754285083e+00 +1.3275630635373319e+00 +1.2818751313820770e-01 +-2.4153833149477273e+00 +1.3853234710228364e+00 +1.4440018500863194e-01 +-2.5764930626755564e+00 +1.2727729688937095e+00 +2.2182292383084068e-01 +-3.5520641487989848e+00 +1.4921598858641256e+00 +1.5629826772908828e-01 +-2.5973613780630878e+00 +1.3481346478849461e+00 +1.4373929909733441e-01 +-2.5097140481595628e+00 +1.1991117601678807e+00 +2.1451123367809280e-01 +-3.4483417507544929e+00 +1.1714803416786990e+00 +2.1432292032271941e-01 +-3.4127969130104634e+00 +1.3185233179391722e+00 +1.4851477063018087e-01 +-2.4346673702582944e+00 +1.3458861195821124e+00 +1.5883692967498317e-01 +-2.5088647026155928e+00 +1.3162762967891928e+00 +1.5817116191106015e-01 +-2.4366984855924732e+00 +1.3355805450169609e+00 +1.6348701095829846e-01 +-2.3519739481492019e+00 +7.3312492233790638e-01 +1.8553459419250487e-01 +-2.9001285852391407e+00 +1.2923982788813593e+00 +2.8650689896190878e-01 +-3.5989572302016635e+00 +1.3725442287778671e+00 +1.6268253129489602e-01 +-2.3067412194886385e+00 +1.3360834369771015e+00 +1.6534864982957287e-01 +-2.3491687327190629e+00 +7.2946895831611325e-01 +1.8908839117579207e-01 +-2.8906626582319337e+00 +1.8131260488175551e+00 +4.2139871712632049e-01 +-4.5402422358339134e+00 +1.3129555991423458e+00 +1.8475938973595130e-01 +-2.4482824244880397e+00 +1.3165230332056463e+00 +1.8683058818866274e-01 +-2.4648634874581261e+00 +7.1507198701625097e-01 +1.9628190633464992e-01 +-2.8784604535008129e+00 +1.3139769070096108e+00 +1.8528219447453897e-01 +-2.4437731185390610e+00 +1.3142141922705839e+00 +1.8706426055507316e-01 +-2.4532374920078794e+00 +5.1539443954574671e-01 +1.6834176065349241e-01 +-2.6856717869234785e+00 +1.3111214897817596e+00 +1.8619953857511165e-01 +-2.4022056244874350e+00 +1.3137972856370712e+00 +1.8647205369733094e-01 +-2.3799730967624209e+00 +1.3107424034825543e+00 +1.8824738462060872e-01 +-2.3998001934878257e+00 +5.2446385940156193e-01 +1.7643600731351700e-01 +-2.6912934191769948e+00 +7.8838437903526748e-01 +2.2181501470610746e-01 +-2.9365953358203822e+00 +1.3990364372855730e+00 +2.2867740615815979e-01 +-2.5992885195770516e+00 +1.3888447662224854e+00 +2.2813338848491763e-01 +-2.6010868414535215e+00 +1.3888447662224854e+00 +2.2813338848491763e-01 +-2.6010868414535215e+00 +1.3356568544228578e+00 +2.1082418450541671e-01 +-2.4097365726438675e+00 +1.3342494413776873e+00 +2.1050869072089648e-01 +-2.4013124753495450e+00 +1.3876214541558909e+00 +2.3892632510341522e-01 +-2.6012284806568045e+00 +9.4622902927758146e-01 +2.7500778551605315e-01 +-3.1290389410971073e+00 +1.8309524390305898e+00 +5.1615686412500172e-01 +-4.6001767042373771e+00 +7.9292066902874325e-01 +2.4630826436966990e-01 +-2.9328216284510851e+00 +6.9124662568620288e-01 +2.2888666494340976e-01 +-2.8395379381083279e+00 +1.3788357358572103e+00 +2.4273540508768190e-01 +-2.5529338156052259e+00 +1.3279140375369438e+00 +2.4545381741691169e-01 +-2.4687791748709569e+00 +1.3279140375369438e+00 +2.4545381741691169e-01 +-2.4687791748709569e+00 +7.2159057918298120e-01 +2.5412641163405286e-01 +-2.8678982445563066e+00 +9.7447403809688715e-01 +3.1686650143773865e-01 +-3.1476889800579086e+00 +1.3281644210369312e+00 +2.5207419167258055e-01 +-2.4621466762944619e+00 +1.3264977105631590e+00 +2.4850265454791920e-01 +-2.4133606520862165e+00 +8.4119329349233185e-01 +2.9058087664717197e-01 +-2.9764534158796496e+00 +8.4359546421594001e-01 +2.9358010380960103e-01 +-2.9770890579568872e+00 +5.9629961699819845e-01 +2.4742637754253499e-01 +-2.7530797646117473e+00 +1.3308051319059553e+00 +2.5472978528228640e-01 +-2.3861915256224391e+00 +1.3299947332591400e+00 +2.5451164418108951e-01 +-2.3708826381091450e+00 +5.7875969013592232e-01 +2.5005939400508836e-01 +-2.7408298694787829e+00 +1.3850640354903094e+00 +2.5792075164921791e-01 +-2.3147598724360203e+00 +4.9182840879346706e-01 +2.5342702913154214e-01 +-2.6775307473246235e+00 +9.1960478331826390e-01 +3.6258766813791588e-01 +-3.0997380324110071e+00 +4.1122152927576161e-01 +2.5065112864201755e-01 +-2.6439358516537315e+00 +1.3309170786495603e+00 +3.0116376679354706e-01 +-2.4622759624954949e+00 +4.0834030573097141e-01 +2.5501213439797554e-01 +-2.6490452819137627e+00 +8.5837916161525041e-01 +4.0459648767628931e-01 +-3.1704567651920641e+00 +8.5540148874470312e-01 +4.0780265520096692e-01 +-3.1639948740286448e+00 +8.5399253090188287e-01 +4.1113028654599693e-01 +-3.1607475987682569e+00 +8.5590455455999948e-01 +4.1381236657047660e-01 +-3.1604242457869933e+00 +4.3817078536255505e-01 +2.8873088732822827e-01 +-2.6495470154605076e+00 +1.8654549544500476e+00 +5.0642084558539968e-01 +-3.0770790380153303e+00 +4.4570904676703377e-01 +2.9171613682966707e-01 +-2.6507463987122684e+00 +1.8653124424037619e+00 +5.1717412299484466e-01 +-3.0748325105424370e+00 +1.8050167379148581e+00 +5.1850998667002424e-01 +-3.0759638878782427e+00 +4.0901371074095383e-01 +3.0277762430780053e-01 +-2.6606766088926306e+00 +4.4113565243208747e-01 +3.1189089690540694e-01 +-2.6603402081914500e+00 +4.4734898291743963e-01 +3.1970272959428858e-01 +-2.6569320768589644e+00 +3.7211339009894268e-01 +3.4683079720487803e-01 +-2.6456964081914482e+00 +5.1754341767981538e-01 +3.7737534695419062e-01 +-2.6973616623951684e+00 +3.7318919277473073e-01 +3.5723251101913489e-01 +-2.6540948771505573e+00 +4.4917497948407353e-01 +3.7505263187643562e-01 +-2.6539831546603025e+00 +4.6711344771433116e-01 +3.9449920466301486e-01 +-2.6708596155206266e+00 +4.4190257501737468e-01 +3.8827410543333624e-01 +-2.6562891771591999e+00 +4.6683584784581245e-01 +3.9964193635001505e-01 +-2.6698090715338290e+00 +5.7547738910005708e-01 +4.4148602057698583e-01 +-2.7339345906525008e+00 +3.1275843448802060e-01 +4.0090279375771221e-01 +-2.6685790729730017e+00 +5.8836597931306978e-01 +4.5416102980918815e-01 +-2.7397571325205843e+00 +5.8836597931306978e-01 +4.5416102980918815e-01 +-2.7397571325205843e+00 +3.1528189332640799e-01 +4.0269897178473768e-01 +-2.6693525081481493e+00 +4.7720119229344093e-01 +4.3072673813664147e-01 +-2.6773611504199173e+00 +4.7649346411080118e-01 +4.3848749545975274e-01 +-2.6807487054732277e+00 +4.8343852707156559e-01 +4.5370216537493802e-01 +-2.6705670509060617e+00 +2.9201981324638165e-01 +4.5385895844517632e-01 +-2.6675511045159466e+00 +5.7205821843484728e-01 +-1.5216040833560779e-01 +-1.8879710962606382e+00 +5.7614462191545057e-01 +-1.3173457244676037e-01 +-1.8851233412789825e+00 +1.3111084900123058e+00 +-1.8009504214653985e-01 +-2.4040987355557601e+00 +1.3111084900123058e+00 +-1.8009504214653985e-01 +-2.4040987355557601e+00 +4.1622418411083428e-01 +-1.5808084480389023e-01 +-2.6493983577900875e+00 +3.9940358029052275e-01 +-1.5401501952482899e-01 +-2.6493252773636247e+00 +4.5609187474285601e-01 +-1.4230605650136316e-01 +-2.6216585105680146e+00 +5.7001243722769213e-01 +-1.0577862450801978e-01 +-1.8988854261948762e+00 +5.0630957381603592e-01 +-1.4542612144869257e-01 +-2.6710781908654480e+00 +5.1409471456129796e-01 +-1.4389124361944855e-01 +-2.6555118179053574e+00 +5.1409471456129796e-01 +-1.4389124361944855e-01 +-2.6555118179053574e+00 +5.7110604989868530e-01 +-1.0463365879168195e-01 +-1.8978005667197779e+00 +5.1620479099174799e-01 +-1.4325645888332808e-01 +-2.6564620917389168e+00 +5.7282655673069771e-01 +-1.0336356151157190e-01 +-1.8972157053306176e+00 +5.7282655673069771e-01 +-1.0336356151157190e-01 +-1.8972157053306176e+00 +5.4621140188460326e-01 +-1.4336370831779990e-01 +-2.6752695913392475e+00 +5.7368789976225043e-01 +-1.0139717783363567e-01 +-1.8957373898007412e+00 +5.7164017538202894e-01 +-1.0038283484268253e-01 +-1.8975452360026610e+00 +5.7164017538202894e-01 +-1.0038283484268253e-01 +-1.8975452360026610e+00 +5.8038881694176658e-01 +-1.0045375281982595e-01 +-1.8919371203991471e+00 +5.7646941423660414e-01 +-1.0035912418923126e-01 +-1.8940926954133841e+00 +5.7846514798099480e-01 +-9.9657783329361371e-02 +-1.8942110649892872e+00 +5.7014901969179310e-01 +-9.5446455515667508e-02 +-1.8958220591168859e+00 +5.7514984659984136e-01 +-9.2502066147244405e-02 +-1.8956854067677202e+00 +4.4675511568057924e-01 +-1.1732612225057211e-01 +-2.5953138174027961e+00 +5.7422688243773978e-01 +-9.0553507857683929e-02 +-1.8948453064897537e+00 +1.1431787524847421e+00 +-1.5858462892768801e-01 +-3.3579383146590427e+00 +4.6981580201391637e-01 +-1.1571607390973565e-01 +-2.6739721309344593e+00 +4.9963543750811323e-01 +-1.1681010775176448e-01 +-2.6876456257024404e+00 +5.6978617974081081e-01 +-8.1747433997446703e-02 +-1.9094813151388963e+00 +5.6727942725824665e-01 +-8.0651894252050896e-02 +-1.9071021794419234e+00 +1.3341411946704855e+00 +-1.1660674975920517e-01 +-2.4799488444421320e+00 +5.9789021734913927e-01 +-1.0456056945608803e-01 +-2.7479468794185244e+00 +7.7809818881658610e-01 +-1.1233497271959965e-01 +-2.9201736767100068e+00 +6.5034282587399572e-01 +-1.0554611696931671e-01 +-2.7951010768258922e+00 +5.5533794770427702e-01 +-9.5048828075993297e-02 +-2.6948906854654733e+00 +8.4205160145543634e-01 +-1.0896549007040909e-01 +-2.9960976149295329e+00 +6.8319136577378270e-01 +-9.6695283539152813e-02 +-2.6981116740434983e+00 +4.6488514951391552e-01 +-8.9302604526793505e-02 +-2.6358734105254769e+00 +5.9364082376474647e-01 +-9.3549831901471633e-02 +-2.7457253752792896e+00 +5.6349995310323631e-01 +-9.0994572638607454e-02 +-2.7023535320891336e+00 +4.9644645713812285e-01 +-8.9194737693266704e-02 +-2.6739665455178776e+00 +4.9066425926473534e-01 +-8.8801762031908843e-02 +-2.6695692061079379e+00 +5.8403300791869828e-01 +-9.0233697840832863e-02 +-2.7365828468287376e+00 +5.8403300791869828e-01 +-9.0233697840832863e-02 +-2.7365828468287376e+00 +5.8878980952093452e-01 +-8.9370743783879436e-02 +-2.7300732822328642e+00 +4.9140980832143227e-01 +-8.6141903347084034e-02 +-2.6699816927404791e+00 +6.1859313644231284e-01 +-9.0112672083018958e-02 +-2.7627032240546563e+00 +8.9061376226362032e-01 +-1.0124893045735339e-01 +-3.0637640896388389e+00 +5.0909726306809555e-01 +-8.5047510325084730e-02 +-2.6781121459794233e+00 +6.2605900100565459e-01 +-8.7692936167821936e-02 +-2.7623053401562498e+00 +5.7642268273639596e-01 +-6.7079833944625133e-02 +-1.8963775190929542e+00 +5.7428626098767943e-01 +-6.6954605088723557e-02 +-1.8928873555755878e+00 +5.7539645929181049e-01 +-8.6532231015738606e-02 +-2.7270670635180854e+00 +4.9778583919166808e-01 +-8.3288220042259387e-02 +-2.6729661083627110e+00 +9.3122379528608812e-01 +-9.6487232672647014e-02 +-3.0902920388124553e+00 +6.1293823992974505e-01 +-8.2769093963790508e-02 +-2.7452177359355319e+00 +5.7746780468121317e-01 +-6.4533322665597637e-02 +-1.8960500591703757e+00 +5.4837563390059996e-01 +-7.9617974818305778e-02 +-2.6810665725688154e+00 +5.6610764596269791e-01 +-7.6200960480803562e-02 +-2.6926668693782139e+00 +5.0445048368352319e-01 +-7.3861147347912340e-02 +-2.6643866263392599e+00 +3.5757710367993162e-01 +-6.8706074759923019e-02 +-2.4885688155435033e+00 +1.3997487196577558e+00 +-8.1638438976850400e-02 +-2.5960554641091966e+00 +1.4003172556855310e+00 +-8.1153318817025713e-02 +-2.5922431297613464e+00 +9.1794192940304009e-01 +-7.9518842457433403e-02 +-3.0917606833190558e+00 +1.3914502688463946e+00 +-8.9072324965183330e-02 +-3.7017481054038988e+00 +9.0321502163827494e-01 +-7.4642453765764727e-02 +-3.0759663340157832e+00 +8.9881146306401949e-01 +-7.2574013846095325e-02 +-3.0733069960495394e+00 +6.3573209374580686e-01 +-6.4937894038404956e-02 +-2.7663647251312726e+00 +5.6597691529353578e-01 +-5.3317317966570604e-02 +-1.9108020143888667e+00 +5.7378360792125782e-01 +-5.2739043321335291e-02 +-1.8900932115360927e+00 +8.0847900154650554e-01 +-6.6827022916775836e-02 +-2.9514915588869313e+00 +1.8560992857047285e+00 +-8.0509936991034842e-02 +-3.4461101724985665e+00 +1.3960463692609617e+00 +-6.7655196249105043e-02 +-2.6031952283285018e+00 +1.8342560100617649e+00 +-7.7524283968820731e-02 +-3.4357928926474961e+00 +3.7705617287248696e+00 +-1.2225064393283383e-01 +-7.6217879815740313e+00 +6.4927574553072998e-01 +-5.6974005979747937e-02 +-2.6277089343912250e+00 +8.5265610534629233e-01 +-6.1056303763695335e-02 +-3.0062365892593541e+00 +3.4024282816296320e-01 +-4.9391097567926597e-02 +-2.6413504186754442e+00 +1.6179822816450566e+00 +-4.6888188891664379e-02 +-3.9864089296069407e+00 +7.8378003074884828e-01 +-4.1514872375331177e-02 +-2.9252265502620345e+00 +1.6118206939799649e+00 +-3.7372572008808204e-02 +-3.9845528747683567e+00 +8.0560827731552664e-01 +-3.7360121886253352e-02 +-2.9505538864522487e+00 +4.2914196014852612e-01 +-2.9592617834431470e-02 +-2.6185143430697253e+00 +5.3079793205221171e-01 +-2.6316508398091489e-02 +-2.6738681421812074e+00 +5.3079793205221171e-01 +-2.6316508398091489e-02 +-2.6738681421812074e+00 +4.4952219265606536e-01 +-2.4310807701206204e-02 +-2.6482095528464620e+00 +1.3197641072099611e+00 +-2.3998331539984062e-02 +-2.4480976105752403e+00 +1.3247639919501040e+00 +-2.3173443979729751e-02 +-2.4674838892342792e+00 +4.0121779784840450e-01 +-2.3513718432160123e-02 +-2.6415501940110198e+00 +1.3212366436536922e+00 +-2.1310132556456779e-02 +-2.4243176314296750e+00 +1.3277833826784258e+00 +-2.1214367862540353e-02 +-2.4273758748686562e+00 +1.3528647052254437e+00 +-2.0660488189703560e-02 +-2.3257647477282757e+00 +1.3850246207016581e+00 +-1.9856681480997319e-02 +-2.2874428568048346e+00 +1.3261666593839172e+00 +-1.8023625107491028e-02 +-2.3841156020649086e+00 +1.3508253095755804e+00 +-1.4914750285717362e-02 +-2.5104598271496807e+00 +1.0044445836503714e+01 +2.0913232148163616e-01 +-1.5468276690506372e+01 +1.5831606243562946e+00 +9.7794488832544883e-03 +-3.9652834429367241e+00 +1.3314433557026333e+00 +-9.1364788711272623e-03 +-2.3732926438298687e+00 +1.5529394636905605e+00 +1.9267422551962975e-02 +-3.9252609396900029e+00 +9.9163644374231446e+00 +3.9193381267402500e-01 +-1.5426309778444798e+01 +1.9783625597576062e+00 +4.6044261833371965e-02 +-3.5660078136122624e+00 +1.4972547473985780e+00 +4.8473431326072618e-02 +-3.8490629434252659e+00 +1.4039172080616951e+00 +4.5344735081098264e-02 +-3.7199001584550020e+00 +1.3892467491266709e+00 +1.6988045483096421e-02 +-2.5967409368517287e+00 +1.3314048092928488e+00 +1.4098211051760979e-02 +-2.4728756214743992e+00 +1.3912851054318822e+00 +1.8425265025106941e-02 +-2.6014196787919541e+00 +8.3241588024840751e-01 +2.2013608882564498e-02 +-2.9806448468793043e+00 +9.6297104178542554e+00 +4.7101458132508944e-01 +-1.5507153511658661e+01 +8.6003728713191507e-01 +2.5261158688883203e-02 +-3.0139275040139974e+00 +3.0959828354889601e-01 +5.7895738114043796e-03 +-2.5561409514483557e+00 +1.8254245843537442e+00 +5.8960468285720165e-02 +-3.2922767063219815e+00 +3.9032408579404665e+00 +2.5729631871393177e-01 +-7.9113294891721289e+00 +3.8490193203818488e+00 +2.5326438236304322e-01 +-7.8134806632346159e+00 +1.6163917755465660e+00 +1.0053337824843261e-01 +-3.9942653904768872e+00 +1.3743945649493121e+00 +4.6183470667655956e-02 +-2.5483499234447677e+00 +3.8953874343599955e+00 +3.1041823268592034e-01 +-7.9682377158487263e+00 +9.9625832839369739e+00 +7.4207592008185341e-01 +-1.5528900865904966e+01 +3.8561412511134541e+00 +3.3565919230095953e-01 +-7.8282183953798139e+00 +3.8561412511134541e+00 +3.3565919230095953e-01 +-7.8282183953798139e+00 +1.0380874103418389e+00 +8.6529921723060704e-02 +-3.2258775882911754e+00 +1.3235568592387539e+00 +6.5804305124413473e-02 +-2.4606499015399361e+00 +9.2649823332433900e-01 +2.8500269271444161e-02 +-1.8685111581111611e+00 +9.3050344170833299e-01 +2.8643874403482913e-02 +-1.8666229411015762e+00 +1.3242915773191131e+00 +7.0772517412242927e-02 +-2.4589243251696007e+00 +1.3243550091137311e+00 +6.8081493146406172e-02 +-2.3989258123263468e+00 +1.3250171704870344e+00 +6.8526103895073590e-02 +-2.3792503079972778e+00 +1.3356245434317888e+00 +6.7188422319756330e-02 +-2.3410866116696889e+00 +5.8337036995271263e-01 +6.7125085139713547e-02 +-2.7246812230639743e+00 +1.3392787443697571e+00 +6.9589291646800333e-02 +-2.3446837319597496e+00 +1.3295075719304494e+00 +7.0743753757769423e-02 +-2.3753680752566808e+00 +1.3493144276744840e+00 +6.9858463843971361e-02 +-2.3235965179391838e+00 +1.8508190214210050e+00 +1.9979499431738235e-01 +-4.4212310722109107e+00 +1.3939259564605209e+00 +8.7043515725787279e-02 +-2.5914753586294346e+00 +1.3638382976962053e+00 +7.1879851241887144e-02 +-2.3109513229288559e+00 +3.8249135532933241e+00 +4.5952534430815611e-01 +-7.8973111609968747e+00 +9.5277567143124320e-01 +1.0853716191884827e-01 +-3.1334269154869547e+00 +8.3980841860860456e-01 +9.8214515468437721e-02 +-2.9902230757381139e+00 +8.3980841860860456e-01 +9.8214515468437721e-02 +-2.9902230757381139e+00 +4.7963544322889567e-01 +7.1600612773754416e-02 +-2.6500314878666491e+00 +4.3850546842031052e-01 +7.0205310855232628e-02 +-2.6391890025329632e+00 +1.3421669086440602e+00 +8.1383917730096927e-02 +-2.3281742970108037e+00 +9.3295325833160170e-01 +4.0941854658081533e-02 +-1.8650026101180304e+00 +4.3669725076106036e-01 +7.2346046075601023e-02 +-2.6339117543521104e+00 +4.3498046892220771e-01 +7.1899345217913607e-02 +-2.6285104919932745e+00 +1.3560988845009656e+00 +8.2582400037084142e-02 +-2.3160438107750050e+00 +1.3513409324233150e+00 +8.3208074657681180e-02 +-2.3190629695219225e+00 +1.3206681341578064e+00 +8.9498543192465432e-02 +-2.4318590251549810e+00 +1.3514338407867166e+00 +8.4797881022458194e-02 +-2.3248983339032607e+00 +1.3486083008995526e+00 +8.5286144174544998e-02 +-2.3290131892236490e+00 +1.3854818581824322e+00 +1.0368361223526866e-01 +-2.5927557347003911e+00 +7.8766452168723700e-01 +1.1309942892180778e-01 +-2.9344758687327284e+00 +1.3291727724738589e+00 +1.0137637934709307e-01 +-2.4123816608509396e+00 +9.2796412066677492e-01 +1.4289393424142482e-01 +-3.1081717324134250e+00 +1.8252374409594212e+00 +2.7785372776575845e-01 +-4.4744979360140587e+00 +8.4694047006289241e-01 +1.3748779072145187e-01 +-2.9892836703439927e+00 +1.0703549033012245e+00 +1.7574554751022900e-01 +-3.2711855665756726e+00 +1.1835948923227084e+00 +1.9284369143579028e-01 +-3.4282946397451064e+00 +5.3317110239533694e-01 +1.1146153609899108e-01 +-2.6952693092411422e+00 +4.3975911410174257e-01 +1.0498525634529095e-01 +-2.6405757171490776e+00 +4.3795455351462931e-01 +1.0915524469473417e-01 +-2.6411143353046382e+00 +1.0047375164424344e+00 +1.7989684325414393e-01 +-3.2029571891372002e+00 +1.3910221401011582e+00 +1.4959092885410888e-01 +-2.5994202174929031e+00 +4.3782492242149240e-01 +1.1352116961491633e-01 +-2.6449091800259348e+00 +4.5367726674536679e-01 +1.1524461777025230e-01 +-2.6509184964200490e+00 +4.5569613046467006e-01 +1.1600869893309863e-01 +-2.6575643724634705e+00 +9.1132522735318644e-01 +1.8228088941692297e-01 +-3.0889940717340281e+00 +8.9784718472035474e-01 +1.8248619092744883e-01 +-3.0731590636331356e+00 +1.3290723877763557e+00 +1.5067872348399905e-01 +-2.4197880311708713e+00 +1.0146048501972407e+00 +2.1067454195579577e-01 +-3.2140256774473479e+00 +8.4353055067280303e-01 +1.8324545528687547e-01 +-2.9966917790362935e+00 +8.4361013345109448e-01 +1.8881594822797851e-01 +-2.9980938331720473e+00 +1.3805154150629981e+00 +1.7889332248893702e-01 +-2.5898579927763956e+00 +1.3493696715352617e+00 +1.5892872827512380e-01 +-2.3429693384684334e+00 +1.3247707862732283e+00 +1.6261382676972572e-01 +-2.3876475803227746e+00 +1.3338425480269511e+00 +1.6388728195396751e-01 +-2.3756608627944806e+00 +5.5447476456083655e-01 +1.5704738673578145e-01 +-2.7120662404889062e+00 +1.0341698794788439e+00 +2.3513322338573386e-01 +-3.2235871227569413e+00 +1.3341822056726076e+00 +1.6583626282858013e-01 +-2.3537181006078360e+00 +1.3685682797338288e+00 +1.6486841212641842e-01 +-2.3150195653590533e+00 +1.8235844461887918e+00 +4.1691014477650351e-01 +-4.5608701638527167e+00 +1.3753948714121487e+00 +1.6478710078778427e-01 +-2.3051730040665230e+00 +8.4507026255467621e-01 +2.0709400205592926e-01 +-2.9985407631463907e+00 +1.8123082802278019e+00 +4.2283641317627824e-01 +-4.5625338953153332e+00 +1.3230467742889052e+00 +1.8514159735825261e-01 +-2.4892761471724274e+00 +1.8234075670937280e+00 +4.3577491979784322e-01 +-4.5918198452220151e+00 +8.4933598351754946e-01 +2.1654101165431872e-01 +-3.0021886468537398e+00 +6.7420825115871730e-01 +1.9210255887040087e-01 +-2.8361182581498321e+00 +5.9784962415744869e-01 +1.7998202223873835e-01 +-2.7571277685226043e+00 +1.0364367586814194e+00 +2.5815268703180155e-01 +-3.2175055838983071e+00 +1.4010269979467587e+00 +2.1268697211763291e-01 +-2.5947058686331803e+00 +1.3659472039484037e+00 +1.8288065131778364e-01 +-2.3160040705928995e+00 +1.3754413230166360e+00 +1.8399103539533396e-01 +-2.3203020181663367e+00 +1.4638394574495219e+00 +2.3569929407691545e-01 +-2.7449568305507932e+00 +9.5636436571672079e-01 +2.5739722301112428e-01 +-3.1403770082421580e+00 +7.8004258777434587e-01 +2.2311743270755496e-01 +-2.9302113302464243e+00 +7.8238855199084989e-01 +2.2420960153775890e-01 +-2.9296955229225183e+00 +1.0124381285400548e+00 +2.6938032378433219e-01 +-3.2059739717542528e+00 +1.3861537779373689e+00 +2.2722469440543835e-01 +-2.6018600029701613e+00 +7.8599554309880904e-01 +2.3117409262443944e-01 +-2.9433659194019821e+00 +1.4612910310161014e+00 +2.5735194474618056e-01 +-2.7630012333092249e+00 +7.6251152208038186e-01 +2.3201796551627965e-01 +-2.9189689413925044e+00 +1.3834281633151919e+00 +2.0012281972203053e-01 +-2.2986261799339713e+00 +1.2966472925180585e+00 +3.6736600944156200e-01 +-3.6972354220286419e+00 +7.8836118474447658e-01 +2.4223597661820739e-01 +-2.9372632201630551e+00 +1.3879711702685191e+00 +2.4265399121063688e-01 +-2.5995947239964265e+00 +1.8142129525315263e+00 +5.0865243445150832e-01 +-4.5627729314994365e+00 +1.3985019278503894e+00 +2.4334065670451402e-01 +-2.5953436486993424e+00 +3.6198804647553451e-01 +1.8116525402352851e-01 +-2.6465983340999077e+00 +8.1295888860687315e-01 +2.4948170622450813e-01 +-2.9537010238916546e+00 +1.2916573098168702e+00 +3.7240478782281167e-01 +-3.7000297811580007e+00 +8.4006357885261995e-01 +2.5614756458373023e-01 +-2.9887254334954725e+00 +1.2925899698510663e+00 +3.7684482247546830e-01 +-3.6980500498139510e+00 +1.2925899698510663e+00 +3.7684482247546830e-01 +-3.6980500498139510e+00 +1.3323916768180473e+00 +2.2138777471287832e-01 +-2.3871076738479236e+00 +1.3252978322829934e+00 +2.2023211706195273e-01 +-2.3795923004051338e+00 +1.3319153767492407e+00 +2.2987284024505467e-01 +-2.4172516738991345e+00 +6.6676386836074797e-01 +2.3707923763472960e-01 +-2.8270622739754501e+00 +6.5216827200120220e-01 +2.3812630096426693e-01 +-2.8068389032420735e+00 +8.1101429552838555e-01 +2.7000983704620035e-01 +-2.9425354111328366e+00 +8.1416328660768134e-01 +2.7160781056840805e-01 +-2.9404996754833070e+00 +8.0748348363396893e-01 +2.7160974741342686e-01 +-2.9414780104905787e+00 +8.0092694383171881e-01 +2.7214530122046265e-01 +-2.9492716538874113e+00 +7.4904055236633316e-01 +2.6500075512436960e-01 +-2.8990969929821668e+00 +1.3244349586415052e+00 +2.6491054023561950e-01 +-2.4834053375519836e+00 +6.4392553397266095e-01 +2.5543687486204369e-01 +-2.7875374952852412e+00 +1.3200656018033881e+00 +2.6506232089219095e-01 +-2.4730328407009159e+00 +1.3215980348956116e+00 +2.5528592655088733e-01 +-2.3754666756264435e+00 +1.3636034916084172e+00 +2.5119635444708877e-01 +-2.3219661094952140e+00 +1.3200532387213459e+00 +2.8004573756374324e-01 +-2.3869481783581730e+00 +6.2023453479721691e-01 +2.8140421927947873e-01 +-2.7646922700362113e+00 +8.6336035532934685e-01 +3.8095124313626538e-01 +-3.1613468663113453e+00 +3.4476141978531322e-01 +2.5585318771687554e-01 +-2.6531141050023783e+00 +8.6245556816039837e-01 +3.9687853828188319e-01 +-3.1680470635740101e+00 +5.2355443294390014e-01 +2.8646908422096223e-01 +-2.6836251744500816e+00 +8.5692111536713156e-01 +3.9884124138413352e-01 +-3.1573301751471781e+00 +5.0523967410488768e-01 +2.8747885916863714e-01 +-2.6755597992621691e+00 +1.4817465725747483e+00 +3.5521771232543964e-01 +-2.5234766897555945e+00 +1.4817465725747483e+00 +3.5521771232543964e-01 +-2.5234766897555945e+00 +1.4898284120740970e+00 +3.5515538782268424e-01 +-2.5182763140195217e+00 +1.4898284120740970e+00 +3.5515538782268424e-01 +-2.5182763140195217e+00 +4.9735928044194805e-01 +2.8756767083416557e-01 +-2.6720660428944494e+00 +1.4841338916358648e+00 +3.5587181917548977e-01 +-2.5224344418000402e+00 +1.4884602872412585e+00 +3.5597780346113406e-01 +-2.5200142213038466e+00 +4.8773188977712217e-01 +2.8612134249238280e-01 +-2.6608610894301932e+00 +8.2196920466626833e-01 +4.1347827071243831e-01 +-3.1800159628906126e+00 +3.7751220762908166e-01 +2.8821309605495976e-01 +-2.6545109278916685e+00 +1.7842197625309015e+00 +5.1166835212751116e-01 +-3.1110623153788124e+00 +1.8708724816304427e+00 +5.1817389680899184e-01 +-3.0707535256749150e+00 +6.3091037023078023e-01 +3.5110118834570375e-01 +-2.7983755244483564e+00 +1.8857781947606778e+00 +5.2686649459535151e-01 +-3.0231557812968655e+00 +1.7961523930556975e+00 +5.3534750303128997e-01 +-3.1016790005093662e+00 +5.4325182999550747e-01 +3.3814540787487013e-01 +-2.7144203641406586e+00 +5.4325182999550747e-01 +3.3814540787487013e-01 +-2.7144203641406586e+00 +5.7967778764315248e-01 +3.5256159252942970e-01 +-2.7419924614426971e+00 +3.4358419174820087e-01 +3.1125112031370905e-01 +-2.6519049593392858e+00 +5.4384963616206494e-01 +3.4988040605643173e-01 +-2.7157637722394736e+00 +5.7870282401159490e-01 +3.7262270405383630e-01 +-2.7238710512241440e+00 +5.6947565880145590e-01 +3.7361099335660375e-01 +-2.7328904968478192e+00 +5.5329659878867432e-01 +3.7973115108037581e-01 +-2.7142371403814942e+00 +4.5132243407642658e-01 +3.5814352919287185e-01 +-2.6556699726988144e+00 +1.8739520470759807e+00 +6.1585631359596960e-01 +-3.0653579076872561e+00 +3.3370718165261620e-01 +3.5270060668531283e-01 +-2.6603263166437414e+00 +3.8074088769911441e-01 +3.6546460182408691e-01 +-2.6530933811515913e+00 +4.6977810068038806e-01 +3.9480192747204995e-01 +-2.6724236854748589e+00 +5.6434393656818438e-01 +4.3229963874956567e-01 +-2.7341016884417479e+00 +5.6082194255905138e-01 +4.3203872255633124e-01 +-2.7308435399616937e+00 +3.1786803737378433e-01 +3.9804091805574537e-01 +-2.6696207399079488e+00 +4.3190049473549252e-01 +4.1300380507104933e-01 +-2.6570580541671123e+00 +5.5716499893818139e-01 +4.7513390630582097e-01 +-2.7370681625384501e+00 +4.0499898891049052e-01 +4.5286170615565696e-01 +-2.6502940811334357e+00 +5.7200155349704351e-01 +-1.5385288171026987e-01 +-1.8867641051050998e+00 +5.7997574801234797e-01 +-1.4502834596443712e-01 +-1.8830599822570626e+00 +5.7616815402287780e-01 +-1.3554358785808882e-01 +-1.8845130224511617e+00 +5.8513613104694784e-01 +-1.3462559266474936e-01 +-1.8788139770499035e+00 +1.3091428171195205e+00 +-1.8294262536220990e-01 +-2.4067582596625359e+00 +1.3065156559326361e+00 +-1.7992303117221606e-01 +-2.4081403499345830e+00 +4.5815399533247719e-01 +-1.4391159951479723e-01 +-2.6369592014270027e+00 +4.6124478532332669e-01 +-1.4581429564371690e-01 +-2.6541265837192745e+00 +4.9884448685298122e-01 +-1.4698239015721337e-01 +-2.6699457331927143e+00 +4.9738170740996068e-01 +-1.4208542520640377e-01 +-2.6460192386660779e+00 +4.9738170740996068e-01 +-1.4208542520640377e-01 +-2.6460192386660779e+00 +1.3564355325261614e+00 +-1.5292621972214659e-01 +-2.3098418380222960e+00 +5.7266083943553814e-01 +-1.0250125221568789e-01 +-1.8980695418260511e+00 +5.8103959248213544e-01 +-1.0174346447321482e-01 +-1.8945670096409297e+00 +5.8932751984345222e-01 +-1.0192508058787351e-01 +-1.8984186334467470e+00 +5.7008148920070345e-01 +-1.0008957899050872e-01 +-1.8966212297074516e+00 +1.3952937881595420e+00 +-1.6184649384911912e-01 +-2.6084995660724952e+00 +5.7483352225121032e-01 +-9.9426657171647462e-02 +-1.8958507255038728e+00 +4.4657957149746774e-01 +-1.3046204221728758e-01 +-2.5950613754614764e+00 +5.7806066875540041e-01 +-9.8701321292842328e-02 +-1.8930389823680649e+00 +5.6910380937374239e-01 +-9.8150961243948301e-02 +-1.8975000548557086e+00 +5.8252337236066121e-01 +-9.7484352258286527e-02 +-1.8939031517213303e+00 +5.6906598403201614e-01 +-9.3939252754782598e-02 +-1.8951645584891967e+00 +5.7556840865933034e-01 +-9.1848428250548536e-02 +-1.8932236980627846e+00 +5.8158000837653478e-01 +-9.0757302140583418e-02 +-1.8958287756521199e+00 +5.7717965432929963e-01 +-9.0631821181502425e-02 +-1.8925481781233215e+00 +5.6520552998480389e-01 +-9.0536620935180168e-02 +-1.9071472535066596e+00 +5.6520552998480389e-01 +-9.0536620935180168e-02 +-1.9071472535066596e+00 +5.7950549988941358e-01 +-8.9869490239097669e-02 +-1.8918885896085269e+00 +5.6543608300882697e-01 +-8.9632377439218106e-02 +-1.9073617643248046e+00 +1.3997940582989579e+00 +-1.3649303381903227e-01 +-2.5951895542519150e+00 +6.0375311169728996e-01 +-1.2910989155352307e-01 +-3.0261477030201118e+00 +8.4579617383184746e-01 +-1.3014732423474976e-01 +-2.9995965584415325e+00 +5.6988564443043244e-01 +-8.2253234908506515e-02 +-1.8980765829750876e+00 +5.7793571790305065e-01 +-8.1437523336161666e-02 +-1.8963893784640407e+00 +5.6877403337973609e-01 +-8.1726116982129324e-02 +-1.9102600453482965e+00 +5.7759988310169630e-01 +-8.1041793095457490e-02 +-1.8978072361129878e+00 +5.8258485179592934e-01 +-8.1003530351666589e-02 +-1.8975991742544407e+00 +5.8163440478748896e-01 +-8.0113368478132857e-02 +-1.8973984103296000e+00 +1.3364396789795567e+00 +-1.1442205426791445e-01 +-2.4268955745058429e+00 +5.6890969935947977e-01 +-7.7285336609293737e-02 +-1.8981150096875041e+00 +5.6746890268780670e-01 +-7.6579410919400154e-02 +-1.9027241504180556e+00 +7.7784740379562822e-01 +-1.1032286751414543e-01 +-2.9148899504930936e+00 +4.7859149256767219e-01 +-9.6223656526512269e-02 +-2.6632557657160403e+00 +5.5737351822172909e-01 +-9.8286732228816703e-02 +-2.7101196730187951e+00 +5.9235482987267896e-01 +-9.8064813938049736e-02 +-2.7420474602301890e+00 +4.3135572744809547e-01 +-9.2067685463522439e-02 +-2.6477615693583978e+00 +6.4891436339580921e-01 +-9.8523073386662594e-02 +-2.7848121678306437e+00 +5.9176279363359208e-01 +-9.5759334294043569e-02 +-2.7313897104008964e+00 +5.8229725138235611e-01 +-9.3133619654133373e-02 +-2.7338985802793676e+00 +5.5177622716685626e-01 +-9.1194877664271617e-02 +-2.6976887493569479e+00 +5.4812352394972041e-01 +-9.0741652423275143e-02 +-2.6880729186557479e+00 +5.0670342796949364e-01 +-8.9367454399418428e-02 +-2.6763936704764806e+00 +5.8515856132067212e-01 +-9.0839152518428209e-02 +-2.7264146673791898e+00 +5.4962265693098966e-01 +-8.9393638250195431e-02 +-2.6897514362179002e+00 +4.6872152253640609e-01 +-8.6468777785896483e-02 +-2.6396031044301433e+00 +5.8561947260909586e-01 +-8.7950410553980202e-02 +-2.7263462575273349e+00 +5.8159900057903136e-01 +-8.8632980523820029e-02 +-2.7338852952836432e+00 +1.3288080791714536e+00 +-9.3567510186969141e-02 +-2.4366732185636564e+00 +5.1227589588432754e-01 +-8.5145170715984070e-02 +-2.6805200152072453e+00 +4.9941206174968522e-01 +-8.4605962280852737e-02 +-2.6748399324985472e+00 +1.3257177578162462e+00 +-9.2105597684543822e-02 +-2.4342450426378908e+00 +5.9310368271539737e-01 +-8.6992283693683475e-02 +-2.7391356807063998e+00 +5.8995267180997057e-01 +-8.6661438377324512e-02 +-2.7311812121544952e+00 +5.4093152293831759e-01 +-8.4084831880241753e-02 +-2.6775787951431433e+00 +5.6768756760902450e-01 +-6.5977893826612316e-02 +-1.9014046113589380e+00 +5.6440542582165676e-01 +-6.2467958984302942e-02 +-1.9011697733463147e+00 +5.8423761638951355e-01 +-6.1434075183878667e-02 +-1.8940058620767959e+00 +9.1401617853163164e-01 +-8.1275735547836334e-02 +-3.0876163240146166e+00 +5.7054039443755000e-01 +-5.8153336238870604e-02 +-1.8954346857900095e+00 +1.3783063275480301e+00 +-7.8376818914098118e-02 +-2.6112801978477491e+00 +5.4333496931106906e-01 +-6.9511625263982926e-02 +-2.6814943747953719e+00 +9.2876349311714179e-01 +-7.7954129606062225e-02 +-3.0790962261511932e+00 +1.0649241809842809e+00 +-7.9092600836280419e-02 +-3.2534132360009385e+00 +9.2065622480879272e-01 +-7.5107866397609677e-02 +-3.0870155967265220e+00 +1.0435820603068608e+00 +-6.9527467024432771e-02 +-3.2304831696954324e+00 +1.8705601065755830e+00 +-7.7923751717591930e-02 +-3.4503528730572515e+00 +1.8628154774508174e+00 +-7.7970580375114923e-02 +-3.4473497993896931e+00 +1.8628154774508174e+00 +-7.7970580375114923e-02 +-3.4473497993896931e+00 +1.8398305518617730e+00 +-7.5684574332363724e-02 +-3.4390375009847864e+00 +1.8398305518617730e+00 +-7.5684574332363724e-02 +-3.4390375009847864e+00 +7.4125098718654614e-01 +-6.1255731076139373e-02 +-2.8819873589499219e+00 +7.4125098718654614e-01 +-6.1255731076139373e-02 +-2.8819873589499219e+00 +5.7026204516952650e-01 +-5.0280880200041005e-02 +-1.8912577839540352e+00 +1.6236098318870404e+00 +-7.6128444386820773e-02 +-3.9931062471810055e+00 +6.1167174118553558e-01 +-5.6024612282447026e-02 +-2.7515430599677373e+00 +1.5868947009540477e+00 +-6.3384825728360433e-02 +-3.9537566242932725e+00 +3.3853182070503174e-01 +-4.8080876129331783e-02 +-2.6403982401595218e+00 +1.0317011584648426e+00 +-4.3779586215948796e-02 +-3.2138515294379517e+00 +1.3489557431566346e+00 +-3.8250368033703713e-02 +-2.5212154455131568e+00 +1.5401722658111194e+00 +-3.4441133401846596e-02 +-3.8890944178002487e+00 +8.0494672026919400e-01 +-3.2140636351078847e-02 +-2.9431293353642705e+00 +8.1840551684937179e-01 +-3.1266752413391656e-02 +-2.9597169694595507e+00 +1.3950529433866519e+00 +-3.2368234330666670e-02 +-2.6019308099533531e+00 +1.3869173317567389e+00 +-2.9387882917241932e-02 +-2.5797320816426637e+00 +1.3767083184802409e+00 +-2.8393168122030129e-02 +-2.6147182071751511e+00 +1.3947028800733392e+00 +-2.8288655199381254e-02 +-2.6035820445427960e+00 +1.3995421791151077e+00 +-2.7886486754174669e-02 +-2.5962703411527883e+00 +1.3224498866147876e+00 +-2.7996332895889660e-02 +-2.3509871199909229e+00 +5.2881102055027041e-01 +-2.6481162549190484e-02 +-2.6727958728520536e+00 +3.8311471303930587e+00 +2.9991484457897510e-02 +-7.7606115005063749e+00 +1.3211075615525423e+00 +-2.1695954010965354e-02 +-2.4373377762806636e+00 +1.3227701433001544e+00 +-1.4949795259669359e-02 +-2.4427085971711877e+00 +7.7741685806494774e+00 +1.6959791063241028e-01 +-1.3438842623180417e+01 +1.3295872999184208e+00 +-1.3102042808430105e-02 +-2.4108195500536298e+00 +9.8144885994893372e+00 +2.7427706819056852e-01 +-1.5422814638431246e+01 +1.9018691227980653e+00 +1.7847234070716988e-02 +-3.4527381543480247e+00 +5.0809561392678804e-01 +-2.3026514289126818e-02 +-1.5676247952512343e+00 +1.6034931032086546e+00 +3.7781723314922716e-02 +-3.9881846319208782e+00 +8.0862235287946871e-01 +1.8231968354680776e-02 +-2.9531196537861395e+00 +1.3534208380882524e+00 +1.7970077481497204e-02 +-2.4982278271840261e+00 +1.3269072253120466e+00 +1.7019465265897413e-02 +-2.4163691531705038e+00 +1.3324714013574355e+00 +2.0262176611475623e-02 +-2.4189051878757852e+00 +1.3480310699888078e+00 +1.9239606002265514e-02 +-2.3381936247710753e+00 +9.8792360395996397e+00 +5.6197796194456373e-01 +-1.5498657186690075e+01 +1.6061794381855112e+00 +7.8478037091130742e-02 +-3.9894918798406440e+00 +1.8662529547159445e+00 +6.5822045637976889e-02 +-3.3975945871049440e+00 +9.8701805039211425e+00 +5.8487982543055217e-01 +-1.5240349930897466e+01 +9.8615906489788010e+00 +6.4058013510915190e-01 +-1.5376870340418087e+01 +9.8318946449402596e+00 +6.3968933493432834e-01 +-1.5334479835120478e+01 +7.6394727477659585e-01 +4.1997553672860483e-02 +-2.9279499285832991e+00 +8.3395651669777726e-01 +5.2018383673260019e-02 +-2.9818288375722206e+00 +9.7590412849043773e+00 +7.1665288099763280e-01 +-1.5208236155109045e+01 +9.5707411161783096e+00 +7.1779890083183751e-01 +-1.5259258304981683e+01 +2.3013339187964039e+00 +1.2985317112177375e-01 +-4.0626454211991243e+00 +2.3073799485948223e+00 +1.3353964567906101e-01 +-4.0642684494003429e+00 +1.3890237867146387e+00 +5.5986878227085209e-02 +-2.5964795500807925e+00 +4.4761237753223843e-01 +3.9911890526466660e-02 +-2.6453939792718817e+00 +3.7853633440119694e+00 +3.5298188025754590e-01 +-7.8765174912908211e+00 +1.3964182003283614e+00 +6.4326548420184607e-02 +-2.5927765532295166e+00 +7.2493649398021276e-01 +6.4079605074546672e-02 +-2.8864066955136276e+00 +1.6492917250764263e+00 +1.4443841919387049e-01 +-4.0671177130041096e+00 +1.3938835658428008e+00 +6.9942541654655382e-02 +-2.6007656633126595e+00 +1.8743575629906719e+00 +1.2617512306250073e-01 +-3.4047608822668041e+00 +1.3239838920384621e+00 +6.8122064059137302e-02 +-2.4552935217168730e+00 +1.3233701242806750e+00 +6.7643467114779490e-02 +-2.4322039303775291e+00 +1.3154042514206490e+00 +6.6938018945208261e-02 +-2.4187917098953866e+00 +1.3220154033102101e+00 +6.9116307285653475e-02 +-2.4015843431596027e+00 +1.3226289184479740e+00 +7.2987646004009366e-02 +-2.4190774563347355e+00 +1.3776722289096459e+00 +8.4889399186776043e-02 +-2.6034351837742515e+00 +1.3917550455232115e+00 +8.6973801169024215e-02 +-2.6005232459822456e+00 +9.7704163768264396e-01 +1.0672052828543029e-01 +-3.1617526668947629e+00 +3.8384758895965403e+00 +4.6177801724606654e-01 +-7.8975497594649555e+00 +1.3328277414663183e+00 +8.1776193862303434e-02 +-2.4756343287132574e+00 +1.3215761993204618e+00 +7.9032900133697959e-02 +-2.4011240793484703e+00 +1.2308679484710170e+00 +1.4838244529087188e-01 +-3.5001872930002840e+00 +1.3227574450831578e+00 +9.0291273430212204e-02 +-2.4526528243584367e+00 +7.2611558671560905e-01 +1.1057648110875599e-01 +-2.8882256301709428e+00 +7.7303649894665072e-01 +1.1779372923075616e-01 +-2.9297339302296161e+00 +1.0297404345087975e+00 +1.5066046300029651e-01 +-3.2178692005054121e+00 +7.2872531815058394e-01 +1.1784970368601799e-01 +-2.8837767384864947e+00 +7.3930482499550099e-01 +1.1993389735552415e-01 +-2.8887599007923188e+00 +1.0710525674809079e+00 +1.6948582902223458e-01 +-3.2709278562888144e+00 +7.8768420586808252e-01 +1.4028752624596427e-01 +-2.9345881869541905e+00 +6.4709567041762628e-01 +1.2492363244102260e-01 +-2.7999933956932197e+00 +4.3687347175255992e-01 +1.0635844212946059e-01 +-2.6409939031157683e+00 +1.0061125692772992e+00 +1.7605568765064655e-01 +-3.2031700217528463e+00 +4.5559390803271849e-01 +1.1481427123178641e-01 +-2.6590076147407671e+00 +1.3509547919308209e+00 +1.4389844922303072e-01 +-2.5170173952135282e+00 +1.1868894940773500e+00 +2.2571320564660907e-01 +-3.4305209891486301e+00 +1.8480079258756288e+00 +3.4891747537812517e-01 +-4.4541562009167901e+00 +8.9294607938503223e-01 +1.8184435182757810e-01 +-3.0667500127917822e+00 +8.9294607938503223e-01 +1.8184435182757810e-01 +-3.0667500127917822e+00 +1.1494169721812384e+00 +2.2537907331981105e-01 +-3.3870653841696443e+00 +9.2926597995969640e-01 +1.9130106986125908e-01 +-3.0893607096514355e+00 +1.3197997833219282e+00 +1.5991671545508829e-01 +-2.4340510038648562e+00 +1.3833236137340224e+00 +1.7869711563345253e-01 +-2.5880648626995391e+00 +1.3203791092633721e+00 +1.6122104740647741e-01 +-2.4269017982204431e+00 +1.3255302711360135e+00 +1.5760998597106754e-01 +-2.3772583991535159e+00 +8.4786420613861224e-01 +1.9456546601685357e-01 +-3.0005268553890279e+00 +1.3270372373986579e+00 +1.6125756694840443e-01 +-2.3838187926662671e+00 +1.3903175776107033e+00 +1.5714669935852801e-01 +-2.2882287858353352e+00 +1.3257691860527736e+00 +1.6275756649822337e-01 +-2.3814679641726815e+00 +1.3391269947152198e+00 +1.6333085801214514e-01 +-2.3434379900875344e+00 +1.3942263886160304e+00 +1.6376934734341925e-01 +-2.2950642311053966e+00 +1.8161603633612946e+00 +4.3322184849096051e-01 +-4.5663129289761679e+00 +1.8232351009572512e+00 +4.3586331147718183e-01 +-4.5811301662018753e+00 +1.3093784575816265e+00 +1.8525586787326820e-01 +-2.4179222089719747e+00 +1.0344827559566974e+00 +2.5722325516491445e-01 +-3.2202670973365839e+00 +6.7948557403245202e-01 +1.9697090263014505e-01 +-2.8416981885199784e+00 +6.7948557403245202e-01 +1.9697090263014505e-01 +-2.8416981885199784e+00 +1.0326767119369673e+00 +2.5874149940287833e-01 +-3.2200319502881429e+00 +4.9804980525012033e-01 +1.7252326435884424e-01 +-2.6785115557549153e+00 +1.3200791097239082e+00 +2.1907439525585320e-01 +-2.4179345771733720e+00 +1.3200791097239082e+00 +2.1907439525585320e-01 +-2.4179345771733720e+00 +1.3699352722522111e+00 +2.1570172072550697e-01 +-2.3407744090404115e+00 +1.8142398219212836e+00 +5.2401907129787983e-01 +-4.5637216814411889e+00 +1.8142398219212836e+00 +5.2401907129787983e-01 +-4.5637216814411889e+00 +1.8027520255084144e+00 +5.3080479735512420e-01 +-4.5446691695414154e+00 +1.7975258464487094e+00 +5.2900547755586080e-01 +-4.5351913199105587e+00 +1.3389274007125858e+00 +2.2086615967387149e-01 +-2.3392624203527022e+00 +1.3257960047288915e+00 +2.3027149347028542e-01 +-2.3955690923407826e+00 +1.3802556094783536e+00 +2.6129299679076473e-01 +-2.6037558054966961e+00 +1.3221446586344563e+00 +2.3552415591507420e-01 +-2.4310478257858525e+00 +1.3872364270626085e+00 +2.6049268157331568e-01 +-2.5879878820308315e+00 +1.3836948910089728e+00 +2.8436886853353166e-01 +-2.7508693235752624e+00 +1.3551285133963589e+00 +2.3216528824500585e-01 +-2.3439885823439996e+00 +1.3236851230240965e+00 +2.3636011351789005e-01 +-2.3789641427419013e+00 +1.3260048552664749e+00 +2.5043132228957915e-01 +-2.4147147201898176e+00 +1.3179181583626323e+00 +2.5270374233446352e-01 +-2.4122403345758729e+00 +1.3242811211411940e+00 +2.5017890461559622e-01 +-2.3807052539825531e+00 +1.3214041555732401e+00 +2.6636295348639810e-01 +-2.4774403747077614e+00 +1.3229427945183789e+00 +2.5319620049394698e-01 +-2.3809405908708214e+00 +1.3516578324159647e+00 +2.5619366737393456e-01 +-2.3503734903101745e+00 +1.3517443041935531e+00 +2.5676827383695056e-01 +-2.3476631194890873e+00 +9.5881802922466675e-01 +3.5032421365097410e-01 +-3.1225072173588848e+00 +1.3198534920111156e+00 +2.7803547939700485e-01 +-2.4297041944915101e+00 +9.6094200021065612e-01 +3.9538694853651768e-01 +-3.3837757858521815e+00 +1.3177353609432865e+00 +2.8164111759813720e-01 +-2.4205431419313888e+00 +1.3258806407475003e+00 +2.7219501541776303e-01 +-2.3404015796443693e+00 +4.1071022602597146e-01 +2.4794771996768764e-01 +-2.6410424404028268e+00 +9.1237478129186134e-01 +3.6885231373801219e-01 +-3.1065381723893344e+00 +9.2104154671038319e-01 +3.7211498397684079e-01 +-3.1111522360214003e+00 +5.4121933185577042e-01 +2.8566426199099426e-01 +-2.6932348976633267e+00 +1.3407857170722439e+00 +3.0465096359231142e-01 +-2.3602007637008846e+00 +5.3536316137643047e-01 +2.8600649557640517e-01 +-2.6899797741290437e+00 +1.5294173634745318e+00 +3.6348110329346472e-01 +-2.5386200320736458e+00 +1.4783831223570605e+00 +3.5567469745593211e-01 +-2.5233128162639598e+00 +8.5059810189269203e-01 +4.1126982692819680e-01 +-3.1778463097630456e+00 +4.8998339884014619e-01 +2.8957879840999451e-01 +-2.6691473849799645e+00 +8.5331843381877648e-01 +4.1301365128270373e-01 +-3.1712161656147098e+00 +8.5129380234141794e-01 +4.1486737306929194e-01 +-3.1765489291038320e+00 +1.7832161741112411e+00 +5.1390071502333212e-01 +-3.1066568439076545e+00 +1.7903473601000195e+00 +5.1832927148216690e-01 +-3.1188964733648672e+00 +6.1515191011149928e-01 +3.4957718555855338e-01 +-2.7819882571963106e+00 +1.8307282564439797e+00 +5.2978929289380550e-01 +-3.0606810795644681e+00 +1.8307282564439797e+00 +5.2978929289380550e-01 +-3.0606810795644681e+00 +1.8952029926596266e+00 +5.4623998088909265e-01 +-3.0891260870720796e+00 +1.8215836552820748e+00 +5.5489150635326334e-01 +-3.1662219608413924e+00 +1.8282865121229912e+00 +5.6011253010029816e-01 +-3.0935837356036378e+00 +1.8376064993971077e+00 +5.6466140014265787e-01 +-3.1065610665044421e+00 +3.3181285528716326e-01 +3.3986768300197207e-01 +-2.6520401205212885e+00 +3.7363586828824391e-01 +4.5032550954952372e-01 +-2.6461945841709040e+00 +5.7327863399990997e-01 +-1.5182551233513919e-01 +-1.8872914636918179e+00 +5.7778942400299116e-01 +-1.3421214298654471e-01 +-1.8837203584156119e+00 +5.6094924441235572e-01 +-1.1503756446344184e-01 +-1.9085502655118987e+00 +5.7689538066737700e-01 +-1.0571368773756161e-01 +-1.8934008850721582e+00 +4.5793691918735435e-01 +-1.3947464409539265e-01 +-2.6243038368735951e+00 +5.0629385898294388e-01 +-1.4236349352478139e-01 +-2.6507922160096795e+00 +5.1417972645005861e-01 +-1.4162340657231945e-01 +-2.6549084773548479e+00 +5.7068421701524052e-01 +-1.0142569838729920e-01 +-1.8958706190731609e+00 +5.7038589722762367e-01 +-9.9218099712708077e-02 +-1.8992362793155921e+00 +5.6945872356585370e-01 +-9.9209076881152242e-02 +-1.8977013488123839e+00 +5.7741184443619897e-01 +-9.7823473229839281e-02 +-1.8924026736277872e+00 +5.7513844188634611e-01 +-9.4700319861605542e-02 +-1.8926757214803835e+00 +5.7508178166013868e-01 +-9.3972202925468831e-02 +-1.8925316595532669e+00 +5.7508178166013868e-01 +-9.3972202925468831e-02 +-1.8925316595532669e+00 +5.6771695034476244e-01 +-8.7786993227266824e-02 +-1.9007748309695023e+00 +5.6820465923799413e-01 +-8.7615026852995451e-02 +-1.8993312963523488e+00 +5.6961434274913414e-01 +-8.1163460255764056e-02 +-1.8985951492052546e+00 +5.4895456676304177e-01 +-9.7235577291263461e-02 +-2.6882153054531743e+00 +5.4895456676304177e-01 +-9.7235577291263461e-02 +-2.6882153054531743e+00 +5.6703909343950243e-01 +-6.7768082511437358e-02 +-1.9011535250136971e+00 +5.6616757645014759e-01 +-6.5292471300352581e-02 +-1.9035800145082964e+00 +5.6869167769892026e-01 +-6.1238699292190557e-02 +-1.8935917673130156e+00 +1.3832634349878139e+00 +-7.9852119037018332e-02 +-2.6137287756174894e+00 +1.6156389184642848e+00 +-8.9935281820112761e-02 +-3.9841375971647564e+00 +1.6427374694847132e+00 +-7.3948831339836527e-02 +-4.0134769464553557e+00 +6.1234876446894160e-01 +-5.4572937467890700e-02 +-2.7509868665714636e+00 +1.6122344551227348e+00 +-3.2732088518034955e-02 +-3.9787709991514308e+00 +4.3820679821304269e+00 +-5.5903830165610728e-03 +-8.3318677504041911e+00 +1.3948470249057421e+00 +-2.5852835985352252e-02 +-2.6018610505211841e+00 +5.2733168567473510e-01 +-2.4926500453220934e-02 +-2.6722141781009503e+00 +4.3341702573170210e-01 +-2.4006709215944312e-02 +-2.6223271360242659e+00 +4.3341702573170210e-01 +-2.4006709215944312e-02 +-2.6223271360242659e+00 +9.1431754076664635e+00 +1.1936883574535490e-01 +-1.4126577605257243e+01 +1.9030951483135568e+00 +4.8261371011508788e-03 +-3.4538731906242148e+00 +9.7810130512867257e+00 +2.4245923379695192e-01 +-1.5305037910470514e+01 +1.3475020642365736e+00 +1.7623732628899064e-02 +-2.4947873175551294e+00 +9.5259398071334367e+00 +4.8978982924438996e-01 +-1.5347462352972832e+01 +1.0100587675403034e+01 +5.0839463289061282e-01 +-1.5561177817867691e+01 +9.7725252395621276e-01 +3.9634876079752947e-02 +-3.1560479665808834e+00 +1.0091790663240609e+01 +5.5214565559536366e-01 +-1.5576027706952496e+01 +1.8734345964107100e+00 +8.5650034387715221e-02 +-3.4064818296026704e+00 +3.8749663425050254e+00 +2.9366268129500739e-01 +-7.8358050770666097e+00 +1.3703190868075437e+00 +4.1182015569198364e-02 +-2.3091884737799853e+00 +1.8718652637747135e+00 +9.7484070782796445e-02 +-3.3947186886073406e+00 +5.9118201968722361e-01 +4.6635236346669301e-02 +-2.7400967935993172e+00 +9.6585295333086805e+00 +7.7194260801381986e-01 +-1.5169630680832078e+01 +1.0347669606439458e+00 +8.1997567119154763e-02 +-3.2255127620638078e+00 +9.6452293141541858e+00 +8.1960645217577455e-01 +-1.5146347813150872e+01 +1.3921804066704142e+00 +6.5512238284574600e-02 +-2.5995338566191717e+00 +8.2119099037202270e-01 +1.1688075293469063e-01 +-2.9622802883101484e+00 +1.8520942583304834e+00 +2.6873653850276114e-01 +-4.3957017270195138e+00 +1.1375156580197168e+00 +1.8673349921319804e-01 +-3.3731297273078744e+00 +1.8408117837831954e+00 +3.3001111677058470e-01 +-4.4302064002359067e+00 +1.8454367149177260e+00 +3.3576486980789044e-01 +-4.4508987394801345e+00 +1.3147917855019116e+00 +1.5287306199207104e-01 +-2.4289937520652800e+00 +1.3142191949420168e+00 +1.5438324205670506e-01 +-2.4286109015648201e+00 +1.3142191949420168e+00 +1.5438324205670506e-01 +-2.4286109015648201e+00 +1.3300444783788510e+00 +1.5510680060065349e-01 +-2.3452603768720146e+00 +1.3376122945402102e+00 +1.5847475542454936e-01 +-2.3453477722059906e+00 +1.3999713971461587e+00 +1.6037377624982266e-01 +-2.2885640320648553e+00 +1.8303741464117140e+00 +4.3227804039140977e-01 +-4.5673107656956811e+00 +1.0342337552298575e+00 +2.5530451622602124e-01 +-3.2205777585068138e+00 +1.3173284944653754e+00 +2.1044084072133662e-01 +-2.4319526033520709e+00 +1.3822602114118074e+00 +2.3678438055657769e-01 +-2.6006488968797368e+00 +7.1543111611915911e-01 +2.3315459020246124e-01 +-2.8746147500740360e+00 +1.8164856524984472e+00 +5.1234289077685413e-01 +-4.5617825173852484e+00 +3.7482720799750524e-01 +1.8606323533392699e-01 +-2.6482318666857791e+00 +1.3253177389234507e+00 +2.2757097706468277e-01 +-2.4104476248979538e+00 +1.3237208860335929e+00 +2.2826277415638341e-01 +-2.3787295100706314e+00 +1.3268202856733935e+00 +2.2848353582409625e-01 +-2.3670279686301035e+00 +9.4043613448744867e-01 +3.6953412641996314e-01 +-3.1241006628887291e+00 +6.9033801017503238e-01 +3.0699933492262299e-01 +-2.8556693130190132e+00 +8.5953355086367755e-01 +3.8454963942480624e-01 +-3.1598846407840639e+00 +4.8188229205853278e-01 +2.8308138877715194e-01 +-2.6703946265483443e+00 +8.5340343350081560e-01 +4.0392519274251709e-01 +-3.1700161894113705e+00 +4.9698090689028102e-01 +2.8597601387463401e-01 +-2.6712156851891948e+00 +8.4654532103555147e-01 +4.1224850665648965e-01 +-3.1795043985803457e+00 +8.4654532103555147e-01 +4.1224850665648965e-01 +-3.1795043985803457e+00 +1.9173730157677282e+00 +5.2007703390504856e-01 +-3.0103934844075400e+00 +3.3741022867636178e-01 +1.0026857406189109e-01 +-2.6814923725385946e+00 +3.3552128619650917e-01 +1.9084083008088146e-01 +-2.6735137607183934e+00 +3.3372846974933351e-01 +1.9108153460624142e-01 +-2.6711019544884160e+00 +3.9004670581654671e-01 +2.1465215391645934e-01 +-2.6562062696242470e+00 +3.9390714308015440e-01 +2.1496745422603111e-01 +-2.6647860073394072e+00 +3.0742557126186959e-01 +3.2377601358053343e-01 +-2.6332392540447973e+00 +2.6875533106597849e-01 +3.2775779561764989e-01 +-2.7476046279930157e+00 +1.3282333234650077e+00 +5.5007314202816474e-02 +-2.4009609486966395e+00 +2.8613539903722507e-01 +1.0333450580851979e-01 +-2.6830158862676448e+00 +1.3389163615063098e+00 +7.9506739784233477e-02 +-2.3699513696961589e+00 +1.9180885889444692e+00 +9.0959507347231031e-02 +-3.4773373713293405e+00 +4.2938930158819083e-01 +2.7891843147043427e-01 +-2.6335722964972774e+00 +3.2545185033928753e-01 +2.8236156326285750e-01 +-2.6697676788618745e+00 +2.3145246627073118e-01 +4.2033917744580979e-01 +-2.7383083053330992e+00 +3.0201427388392088e-01 +4.3063453675813218e-01 +-2.7286225239773003e+00 +5.2971901667192434e-01 +1.1604962898119670e-01 +-2.6895825038233148e+00 +3.0651697858990246e-01 +1.1724406559154686e-01 +-2.6608113255478796e+00 +8.5842259141977417e-01 +2.0205455043711959e-01 +-3.0090903369337259e+00 +5.0590758672580982e-01 +2.0155024555246268e-01 +-2.6940681476241441e+00 +3.2857679384721589e-01 +2.4727565228630946e-01 +-2.6576308130970094e+00 +8.1682762626432925e-01 +2.9413730693853818e-01 +-2.9605033083321199e+00 +4.5580207762398073e-01 +3.0234819286753045e-01 +-2.6507362686179814e+00 +3.1277238276683234e-01 +3.0587159715096784e-01 +-2.6704340437316954e+00 +3.1723211101196724e-01 +3.2758602487522614e-01 +-2.6782995329997683e+00 +3.5043676468082557e-01 +3.7633482584328620e-01 +-2.6587817655072410e+00 +3.2256033716089944e-01 +4.1608000926444305e-01 +-2.6767430475065290e+00 +3.1655095780561832e-01 +4.1593912326364063e-01 +-2.6647501417735699e+00 +2.6349882780908984e-01 +4.3240724226050342e-01 +-2.7145425404816570e+00 +-4.3206985328905240e-01 +-1.0501431747629744e-03 +-6.4328365038781554e-01 +4.4979371888002512e-01 +-2.5487771792557602e-02 +-2.6504476096476619e+00 +3.7349699031363137e-01 +2.4979889157747400e-02 +-2.6434263034281127e+00 +3.2923205900000679e-01 +2.6483166129496281e-02 +-2.6492685329628443e+00 +1.9931522343488912e+00 +2.8937185723879884e-02 +-3.5795544179955852e+00 +3.1622026807643333e-01 +7.2705153928501631e-02 +-2.6570134113415627e+00 +3.8974409537197718e-01 +9.3706522569909786e-02 +-2.6562247852225487e+00 +3.2003728382518348e-01 +1.0204625441180262e-01 +-2.6564524167760299e+00 +3.4522167691499062e-01 +1.1617052970763735e-01 +-2.6625306741733650e+00 +5.3509413533992545e-01 +1.3955481854393845e-01 +-2.6971144911158529e+00 +6.3917099896676310e-01 +2.0674060845533168e-01 +-2.7977916394023095e+00 +4.9861628870881680e-01 +2.3371796050038723e-01 +-2.6810612402907283e+00 +3.4486359682313278e-01 +2.3192302671997342e-01 +-2.6640326787094062e+00 +3.6564243580222749e-01 +2.4189764399952809e-01 +-2.6562013511357110e+00 +5.8782988415141824e-01 +2.5583018644611516e-01 +-2.7455181927032397e+00 +5.8677581776256871e-01 +2.5549136095636144e-01 +-2.7436723333726256e+00 +2.9944749125212267e-01 +3.2047894892918261e-01 +-2.6862700259263161e+00 +4.6175809603491214e-01 +3.4358292392118733e-01 +-2.6623189262073548e+00 +2.8892937104302868e-01 +3.3758470936910279e-01 +-2.6899549519517443e+00 +3.0029431856758854e-01 +3.5186066732457366e-01 +-2.6883887774238731e+00 +3.6983494302756420e-01 +3.7472261070262375e-01 +-2.6468841570697883e+00 +2.5664271209218653e-01 +4.0681840722889867e-01 +-2.6947498263757610e+00 +2.0760407727523242e-01 +4.2677318127743963e-01 +-2.7372075787531158e+00 +3.2452954455532412e-01 +8.4597568289878314e-02 +-2.6527011509193277e+00 +7.1798761748326645e-01 +8.3992949354543378e-02 +-2.8655605589806181e+00 +3.5643922070184839e+00 +7.9434851814177657e-02 +-6.3714470987246914e+00 +3.7651116850308958e-01 +1.3231337280650227e-01 +-2.6601199145283889e+00 +3.7609616963539233e-01 +1.3219615761411402e-01 +-2.6595637166554251e+00 +1.3279850133459199e+00 +1.3433777725004808e-01 +-2.4511857506354242e+00 +4.0305629336350024e-01 +1.6806973899349067e-01 +-2.6484963272530924e+00 +3.6536122328006987e-01 +1.7327853925157244e-01 +-2.6567793725266600e+00 +6.5351888776261291e-01 +2.3802463602442106e-01 +-2.7995685539523469e+00 +4.2715805414549790e-01 +2.5632411230266483e-01 +-2.6601218502503814e+00 +4.2580553810985106e-01 +2.5606397569356304e-01 +-2.6576638347544925e+00 +3.5470689359931451e-01 +2.5770065362019573e-01 +-2.6542630866093861e+00 +3.5470548056278689e-01 +2.5770782424834698e-01 +-2.6542603367236604e+00 +6.2804390468770022e-01 +2.7199093290536980e-01 +-2.7805920399743669e+00 +5.2428535438612789e-01 +3.0114936551376720e-01 +-2.6931291615750319e+00 +2.9269543607436993e-01 +3.0947682494218076e-01 +-2.6979080313236814e+00 +2.8205264366019028e-01 +3.2227012912328717e-01 +-2.6967382799476787e+00 +5.2934516919773555e-01 +3.6967809356652936e-01 +-2.6914691495093508e+00 +2.1658883705812002e-01 +3.6231883353033117e-01 +-2.7284021075343485e+00 +2.1691264695266158e-01 +3.6245896075011702e-01 +-2.7298290126152280e+00 +4.0313808897428344e-01 +3.7315584529957935e-01 +-2.6536099788702456e+00 +2.6054147585017945e-01 +3.7838824980976549e-01 +-2.7000229961643489e+00 +2.6008327637923667e-01 +3.7825853492317957e-01 +-2.6994761518701518e+00 +2.3874229572699601e-01 +4.0360422659277617e-01 +-2.7045397097015353e+00 +2.4503951709823005e-01 +4.0437219652167528e-01 +-2.7175871728281185e+00 +2.1467603014613909e-01 +4.0545308281511744e-01 +-2.7492594266802275e+00 +2.1457915242098061e-01 +4.0538655671109280e-01 +-2.7492643703750290e+00 +4.9492105300845385e-01 +4.2823595204967063e-01 +-2.6931143776570061e+00 +1.8475470003298653e+00 +5.2209942986514135e-01 +-3.0430158132903831e+00 +-3.7509470224253288e-01 +-4.7050897948049068e-03 +-6.5983408306856872e-01 +3.9273861620803813e-01 +-2.3813271749843875e-02 +-2.6676053584509409e+00 +4.2043083829153177e-01 +4.2409513535022765e-04 +-2.6554523426794732e+00 +5.9302724101865234e-01 +6.4269769903959745e-02 +-2.7304525585323356e+00 +5.4591718626119623e-01 +6.6829508099284562e-02 +-2.6972010797482544e+00 +3.5482010376793344e-01 +7.1926939476388452e-02 +-2.6491512244050281e+00 +2.9848478010648788e-01 +7.3386569599532589e-02 +-2.6653820626354956e+00 +1.9185653658366628e+00 +5.5199321505820569e-02 +-3.4786219069083120e+00 +3.7363193924462940e-01 +8.2363332354777843e-02 +-2.6562206378282411e+00 +1.3846778667903192e+00 +7.4416254910796495e-02 +-2.5987459504308807e+00 +2.0197445572103767e+00 +8.0273271670502924e-02 +-3.6313231321403503e+00 +3.6452053270315238e-01 +1.2235093636891288e-01 +-2.6630526336287041e+00 +3.6452053270315238e-01 +1.2235093636891288e-01 +-2.6630526336287041e+00 +4.3877983739170640e-01 +1.2420128018733796e-01 +-2.6524694216476519e+00 +3.6598925902860874e-01 +1.4481667298204631e-01 +-2.6633788049771505e+00 +3.7197472907634754e-01 +1.5252228902313975e-01 +-2.6542295274581584e+00 +1.3287826504398754e+00 +1.6375860002256665e-01 +-2.4046423562732429e+00 +2.7453527750372791e-01 +1.7870651815998431e-01 +-2.6932268520113931e+00 +3.6519400502865756e-01 +1.9217639334832756e-01 +-2.6597321546156230e+00 +7.2821019842580237e-01 +2.2156167457421572e-01 +-2.8816366793113852e+00 +3.6337807061513822e-01 +2.2274388504972203e-01 +-2.6572538676362658e+00 +4.3189916694829128e-01 +2.3222856331713398e-01 +-2.6606486275179315e+00 +3.0556486371154756e-01 +2.4222096564657963e-01 +-2.6908176957641472e+00 +1.7077200736357641e+00 +2.8790137063368709e-01 +-3.1181002837345635e+00 +7.5707644392655993e-01 +2.8005282510731050e-01 +-2.9046328072008865e+00 +3.9971644696498093e-01 +2.7452849974306037e-01 +-2.6559317340056352e+00 +3.3146758581674607e-01 +2.8240457718993711e-01 +-2.6522802220087289e+00 +3.2207194506806264e-01 +2.8322435535987445e-01 +-2.6649643754217553e+00 +3.0668892433601069e-01 +3.0951556867392033e-01 +-2.6984731046109132e+00 +5.6419264916564416e-01 +3.4547640558191511e-01 +-2.7224277093368703e+00 +2.0353023674815635e-01 +3.7427251457462435e-01 +-2.7501460744062536e+00 +2.1681015944405241e-01 +3.8653472496361174e-01 +-2.7351391427994547e+00 +5.0858321331228040e-01 +3.9688452420317372e-01 +-2.6955141803331757e+00 +4.7661502344850315e-01 +4.0721729118416600e-01 +-2.6796509614880417e+00 +5.1232936908507265e-01 +4.1404938608951386e-01 +-2.7026936137675919e+00 +3.0932614604676040e-01 +4.0575492548292896e-01 +-2.6856984166955957e+00 +1.8330618574603386e-01 +4.0969648586313800e-01 +-2.7819229732884709e+00 +2.1990573227102891e-01 +4.1398557797938218e-01 +-2.7437695844602801e+00 +4.6770817190445396e-01 +4.2185037564355521e-01 +-2.6727339080902084e+00 +1.7754970295871704e+00 +5.0740313962972372e-01 +-3.0867615194341371e+00 +1.9024289553262211e-01 +4.1959300781183279e-01 +-2.7754468246761066e+00 +1.9040149991849231e-01 +4.3413927203616354e-01 +-2.7759841109061898e+00 +3.7163481826877764e-01 +-3.0204623509523333e-02 +-2.6484410590075629e+00 +3.7239327800640459e-01 +9.6758399947333273e-03 +-2.6498912820276157e+00 +1.3270227381562072e+00 +-2.4064420367248392e-04 +-2.4337983077711991e+00 +1.3878039042817698e+00 +1.0968017673900132e-02 +-2.5767397626545852e+00 +3.9930815686725246e-01 +3.7818387363622398e-02 +-2.6571472598900963e+00 +3.6280775621753675e-01 +3.8580558407495330e-02 +-2.6545579912792157e+00 +3.9923762693308695e-01 +4.9844574611386409e-02 +-2.6434656798904750e+00 +5.2664875453438598e-01 +7.6268242691272164e-02 +-2.6984588843490735e+00 +3.5019105631578479e-01 +8.1466139018258887e-02 +-2.6520930046198736e+00 +3.6049054206017944e-01 +8.7422232350376022e-02 +-2.6546519072610915e+00 +4.1614055670364286e-01 +8.7035844008875304e-02 +-2.6546568123319507e+00 +4.0778394578836774e-01 +8.9521857535495325e-02 +-2.6564578428166357e+00 +4.0768043395938508e-01 +8.9417528361982093e-02 +-2.6563653567337413e+00 +4.0830112429599269e-01 +1.0111417926088344e-01 +-2.6574280609455876e+00 +5.2148897745600264e-01 +1.0899203057376371e-01 +-2.6868996481464924e+00 +4.2939604399915848e-01 +1.3351962046339697e-01 +-2.6571029225027250e+00 +3.5744009626102718e-01 +1.5233441039467438e-01 +-2.6631012280599711e+00 +3.0535901365655171e-01 +1.6079134274692289e-01 +-2.6699243905206567e+00 +3.0504291445109954e-01 +1.6068992458011810e-01 +-2.6698235295992441e+00 +2.9406109390918433e-01 +1.6934883815678362e-01 +-2.6811073587814702e+00 +2.3008599453558021e+00 +1.9678376216075605e-01 +-4.0574376922417423e+00 +5.1936425824860966e-01 +1.8372659785140091e-01 +-2.6857721262574032e+00 +1.3857997800454338e+00 +1.8795293614970437e-01 +-2.5912278007863865e+00 +5.8147354406624807e-01 +1.9067565665610683e-01 +-2.7366434994491260e+00 +2.2606487155064823e+00 +2.2395626170941108e-01 +-3.9628035972730258e+00 +4.1848408891859157e-01 +1.8946012711585383e-01 +-2.6580406864124484e+00 +3.2315372835801565e-01 +1.8949689723473540e-01 +-2.5223154210549694e+00 +1.3238719624273849e+00 +2.1907947148816845e-01 +-2.4460097802682141e+00 +6.0622703279794565e-01 +2.5652639226383334e-01 +-2.7612518786873546e+00 +6.2400117653293963e-01 +2.6153714227926872e-01 +-2.7723268936926400e+00 +3.4483105569266431e-01 +2.8341155700977838e-01 +-2.6541893782383332e+00 +2.8288240760421940e-01 +3.0975159634775212e-01 +-2.7024357252008628e+00 +3.2281033649547547e-01 +3.4139578944059829e-01 +-2.6765806989598602e+00 +3.3338133924869739e-01 +3.4431268725846892e-01 +-2.6624733677669954e+00 +3.6695959043041443e-01 +3.5233158858986824e-01 +-2.6561354917168423e+00 +1.8819900311553437e+00 +4.6456769827428962e-01 +-3.0390525117277236e+00 +1.8819900311553437e+00 +4.6456769827428962e-01 +-3.0390525117277236e+00 +1.7607568389563699e-01 +3.8687615232005418e-01 +-2.7814136524247686e+00 +2.5475398396145860e-01 +3.8803380441760399e-01 +-2.6936844864436393e+00 +2.7654083816788538e-01 +4.0981783346981365e-01 +-2.7056438656894404e+00 +3.0945942600742282e-01 +4.1284925676758261e-01 +-2.6736915683080236e+00 +6.1815958350990374e-01 +4.3537088573903432e-01 +-2.7957145898554541e+00 +3.4503870267309361e-01 +4.2497965446544894e-01 +-2.6632841928126907e+00 +2.7134870839364278e-01 +4.2741056497804031e-01 +-2.6972076127041911e+00 +2.7261800797278690e-01 +4.3703337564432432e-01 +-2.6983285552836480e+00 +4.1547060740797664e-01 +4.4199814234640550e-01 +-2.6648000254277067e+00 +1.9689878994527812e-01 +4.4239662429134352e-01 +-2.7702497726972100e+00 +3.8458439346208556e-01 +4.5066281621887017e-01 +-2.6562453797327170e+00 +-4.2414987099031143e-01 +1.5236284580477369e-02 +-6.4758622265787780e-01 +-4.4218928951807285e-01 +3.5655726980428404e-02 +-6.5681654434070469e-01 +5.9385331213880077e-01 +-8.5898113097420181e-02 +-3.4200510968515743e+00 +3.1458553459630284e-01 +-4.8564464789138694e-02 +-2.6652721798063332e+00 +6.5050342627464031e-01 +-5.8685405291112103e-02 +-2.7923415819490689e+00 +4.0321186748154902e-01 +-2.8646294859093164e-02 +-2.6598998571072374e+00 +4.0542929114197856e-01 +-2.5011596315620468e-02 +-2.6461424787629118e+00 +1.3248451565928132e+00 +-2.8651465420395823e-02 +-2.3619461978710152e+00 +1.4001870088279980e+00 +-1.8961565815627406e-02 +-2.5861896152554462e+00 +2.5633320969633866e+00 +-6.6172289117239047e-02 +-4.4196251758159040e+00 +5.2614028492734277e-01 +4.0946927141870801e-02 +-2.6904846812048069e+00 +4.0212540965335852e-01 +5.5679092196603136e-02 +-2.6426727021329723e+00 +4.0620577102799577e-01 +6.4003064050983438e-02 +-2.6497722143350737e+00 +1.4381096712545993e+00 +5.2899036416771884e-02 +-2.7168615280242729e+00 +6.7761473216132806e-01 +6.3370693478925780e-02 +-2.8254545531040107e+00 +1.3867828966027163e+00 +6.2522467457470671e-02 +-2.5796097005400402e+00 +5.3139290686273943e-01 +8.0340371288187579e-02 +-2.6927086334850934e+00 +3.9642512162181393e-01 +8.5561486371104820e-02 +-2.6560992464254629e+00 +1.3272298555526603e+00 +8.2693208180201386e-02 +-2.4738180197355613e+00 +5.4444932449931371e-01 +9.4445444563576106e-02 +-2.6988913095475304e+00 +1.3249050016619308e+00 +8.9709947583407265e-02 +-2.4584519269683898e+00 +1.3896492478841447e+00 +9.0771741902435449e-02 +-2.6034743709528891e+00 +5.3069885409917583e-01 +1.0149365174356191e-01 +-2.6896352068510669e+00 +3.2134910571597963e-01 +1.0686630075408056e-01 +-2.6620433342693386e+00 +1.8564872927143634e+00 +9.9054267615063460e-02 +-3.3767956909765799e+00 +3.4978291564004205e-01 +1.4493005717785107e-01 +-2.6615342469457390e+00 +1.7030569232160653e+00 +1.5879108861065208e-01 +-4.1210658432947511e+00 +1.3750199916586527e+00 +1.4722522472137251e-01 +-2.6057507972169365e+00 +2.2310191103355903e+00 +1.6543560730765317e-01 +-3.9329094991922169e+00 +2.2283153736250392e+00 +1.6561217235672171e-01 +-3.9304383342268441e+00 +2.0817908047676683e+00 +1.7060323107845254e-01 +-3.6586227829867775e+00 +2.2557696438329695e+00 +2.0298524712956093e-01 +-3.9613070460278710e+00 +3.0306650240607658e-01 +1.7590408456503642e-01 +-2.6811290495922169e+00 +3.7368461211826459e-01 +1.8724243492045187e-01 +-2.6568759509355813e+00 +1.3371019985892620e+00 +2.1546762617966633e-01 +-2.4149120334424889e+00 +6.5211858569587811e-01 +2.3302056891617604e-01 +-2.8037096187911503e+00 +4.2020870049066322e-01 +2.3800208038459356e-01 +-2.6593996203997707e+00 +4.7874174182929441e-01 +2.4249676516724045e-01 +-2.6678004944638385e+00 +7.3642329203074008e-01 +2.7783904383754843e-01 +-2.8887228495442447e+00 +7.3642329203074008e-01 +2.7783904383754843e-01 +-2.8887228495442447e+00 +3.4775583636930180e-01 +2.6506854323952800e-01 +-2.6611877362717840e+00 +3.4967678604025670e-01 +2.6528184386478781e-01 +-2.6648497658931238e+00 +3.6849868729424601e-01 +2.6663950251705548e-01 +-2.6654971546029751e+00 +3.1175834242932926e-01 +2.7108809789475213e-01 +-2.6670510318096294e+00 +4.3723966994032931e-01 +3.3075738676386029e-01 +-2.6591982457810559e+00 +1.8804042906186194e+00 +4.3608819182580066e-01 +-3.0373339131175627e+00 +1.8810085235910383e+00 +4.4714696929659054e-01 +-3.0382957626710207e+00 +4.6044773890462731e-01 +3.9350050933705050e-01 +-2.6594010602400067e+00 +3.5296357594826205e-01 +4.1271451498055395e-01 +-2.6600449970414117e+00 +2.4760872994428515e-01 +4.2779809851923473e-01 +-2.7212283054180024e+00 +2.4686371555377720e-01 +4.2719695477920944e-01 +-2.7195292687320394e+00 +3.0568311551707034e-01 +4.3761440452873834e-01 +-2.6802779642217947e+00 +2.8475844432027891e-01 +4.3987133661620220e-01 +-2.6985055824841333e+00 +4.6435279025470039e-01 +4.5404065653780279e-01 +-2.6963200958008176e+00 +3.6828207321690054e-01 +4.5102454997241770e-01 +-2.6566926768492416e+00 +3.7968685825186632e-01 +4.5694980326642376e-01 +-2.6595825178360397e+00 +-4.3388903984566113e-01 +-9.2125531639981172e-03 +-6.4216391451788701e-01 +-4.3847242480278675e-01 +9.6951842931892410e-03 +-6.4724128983703300e-01 +3.2486031150114225e-01 +-6.5854469185920736e-02 +-2.6568813024491331e+00 +3.2100090940560511e-01 +-6.0916789163310531e-02 +-2.6607018275936909e+00 +5.5642478135864415e-01 +-6.4470897868107654e-02 +-2.7055837640309210e+00 +3.1088070106427085e-01 +-5.3433139664566559e-02 +-2.6551459109004854e+00 +1.3809443828529997e+00 +-8.0664099997576663e-02 +-2.6060659565629227e+00 +3.3476193379372771e-01 +-4.7896418427702564e-02 +-2.6448912827347142e+00 +3.2269495079536575e-01 +-4.8441013307324421e-02 +-2.6585556583829000e+00 +4.3951612322442402e-01 +-5.0230179632056247e-02 +-2.6447193148661992e+00 +5.7567059209592597e-01 +-5.3761118263669416e-02 +-2.7271376929770992e+00 +1.3300995509747722e+00 +-4.8666411821400281e-02 +-2.3853109579237057e+00 +1.3300995509747722e+00 +-4.8666411821400281e-02 +-2.3853109579237057e+00 +4.6125404360032507e-01 +-2.1839130732609884e-02 +-2.6585082359527328e+00 +5.3768065121206832e-01 +-1.9890969845958027e-02 +-2.6971257385939578e+00 +1.3993746529995497e+00 +-3.9329463796926631e-02 +-2.6013674283613746e+00 +1.3347137714744024e+00 +-2.9834822399232248e-02 +-2.3896968742582549e+00 +5.4418737472070422e-01 +3.4182090228427664e-02 +-2.6986204987835496e+00 +4.6756258151949276e-01 +4.5864224755053994e-02 +-2.6634765955874715e+00 +3.4000312645500996e-01 +4.7593778153432229e-02 +-2.6538854832274450e+00 +1.8529281719619928e+00 +4.1217180693231242e-02 +-3.3777675567080943e+00 +1.8639641136895260e+00 +5.9930098782766374e-02 +-3.3797356629357549e+00 +3.7996827811236727e-01 +8.4816181747757263e-02 +-2.6529790309087518e+00 +1.8657539256378071e+00 +6.6387285638191657e-02 +-3.3917425044157072e+00 +1.8657539256378071e+00 +6.6387285638191657e-02 +-3.3917425044157072e+00 +6.4138646592287851e-01 +8.4814618247840493e-02 +-2.7937244033077784e+00 +1.8606656876043912e+00 +8.9129925286849501e-02 +-3.3967493846564061e+00 +1.0039974878167399e+00 +9.9025898358644532e-02 +-3.1965694303604417e+00 +1.8346480778260057e+00 +9.3285089243765884e-02 +-3.3415570542729340e+00 +8.8472921021559858e-01 +1.0556318726216866e-01 +-3.0472015869541891e+00 +3.2122745599129643e-01 +1.1227884655671905e-01 +-2.6513648178662499e+00 +1.0340492442095088e+00 +1.1326660217917878e-01 +-3.2235126038076585e+00 +1.8534953309057227e+00 +1.1427674656591631e-01 +-3.3850116700672834e+00 +1.0152406496775639e+00 +1.1899577791776818e-01 +-3.2054215540710755e+00 +1.3221836462800132e+00 +1.3455221755161656e-01 +-2.4265272013517989e+00 +1.3220785766065801e+00 +1.4525745803635859e-01 +-2.4422434213384800e+00 +1.3859606757426954e+00 +1.4712427631846817e-01 +-2.5972957214316317e+00 +4.2569444463415079e-01 +1.4885964465005741e-01 +-2.6520711678964282e+00 +3.0607066784265619e-01 +1.4897828812591271e-01 +-2.6728556461257598e+00 +3.7037869819916414e-01 +1.5054813958461735e-01 +-2.6568123706321889e+00 +6.3053925432515390e-01 +1.6061279496296621e-01 +-2.7877837231647056e+00 +6.3074222082627662e-01 +1.6056061925039622e-01 +-2.7878969090359385e+00 +3.7804073388262499e-01 +1.7827373051983836e-01 +-2.6544523920657581e+00 +4.0824783150335264e-01 +1.8596895449642761e-01 +-2.6554535802782100e+00 +1.3826575182400149e+00 +1.9333717671891285e-01 +-2.5942810517923975e+00 +2.2572396269989641e+00 +2.2747087820985371e-01 +-3.9764957812681589e+00 +2.2901110991804194e+00 +2.5229310739584210e-01 +-3.9131074572576381e+00 +2.2901110991804194e+00 +2.5229310739584210e-01 +-3.9131074572576381e+00 +8.2583637386314079e-01 +2.2371313600094592e-01 +-2.9588773831351447e+00 +1.8642532932433478e+00 +2.8152969446967685e-01 +-4.3974296026256026e+00 +1.4688230816667835e+00 +2.4435589066394484e-01 +-2.7699026668946081e+00 +1.3284385099610776e+00 +2.3678939622286466e-01 +-2.4065229008870070e+00 +8.4194364375193553e-01 +2.4726765507742848e-01 +-2.9847109576356941e+00 +1.3216684304488957e+00 +2.4495177397325191e-01 +-2.3888579236640619e+00 +8.0413017808046205e-01 +2.6594792506997655e-01 +-2.9398758197286647e+00 +3.7106471569733096e-01 +2.5126082441988351e-01 +-2.6507065679589630e+00 +4.7584637171992716e-01 +2.6325232231088019e-01 +-2.6680183743220165e+00 +4.6550188084420774e-01 +2.6495562703124242e-01 +-2.6686791575057125e+00 +4.2991162206604366e-01 +2.6464967329889016e-01 +-2.6659127668414526e+00 +1.3127623872484766e+00 +2.7328135041950335e-01 +-2.4238485215798353e+00 +3.3239164954269118e-01 +2.6652949535548548e-01 +-2.6604623490787813e+00 +4.8097107128777777e-01 +2.7724717319310499e-01 +-2.6674131197183444e+00 +4.8122953139594338e-01 +2.7733701504409880e-01 +-2.6678943476095633e+00 +1.3408762853899370e+00 +2.8747089746010257e-01 +-2.3524377449689764e+00 +2.3032035983506751e+00 +4.3494514028347214e-01 +-3.9001378856295372e+00 +2.2888928967910296e+00 +4.3434636573671992e-01 +-3.9025586718996483e+00 +9.9999628855105915e-01 +3.9411835252366051e-01 +-3.3468437282663999e+00 +1.0175756956241446e+00 +3.9419221017821676e-01 +-3.3420526634561467e+00 +1.0083877949891180e+00 +3.9397758948258760e-01 +-3.3414675962465843e+00 +3.0212368624720393e-01 +3.5056789878750472e-01 +-2.6876995794120351e+00 +3.6252954882391714e-01 +3.5814959246580014e-01 +-2.6588002799460275e+00 +3.6372439677778212e-01 +3.6275226524922005e-01 +-2.6550010385467266e+00 +2.6131533544487640e-01 +3.8198526096978841e-01 +-2.6960753589465281e+00 +5.4859893105827873e-01 +3.9564957861183842e-01 +-2.7101561614433178e+00 +4.3948749122705061e-01 +3.9573234201499019e-01 +-2.6617236755058915e+00 +4.2018322892514010e-01 +3.9853050216280922e-01 +-2.6592820933942201e+00 +4.7921651772144508e-01 +4.0903660581689416e-01 +-2.6737470787077506e+00 +5.2877149102549159e-01 +4.2068766596039980e-01 +-2.6998617162471823e+00 +3.0308024815324386e-01 +4.2006165293421105e-01 +-2.6920925414491386e+00 +3.3785188646208875e-01 +4.2706073456249144e-01 +-2.6715075123489953e+00 +2.4814707183565723e-01 +4.3825378321042063e-01 +-2.7217068023327076e+00 +1.7858335736126656e+00 +5.3799146601434034e-01 +-3.0935716837677569e+00 +1.7877820519242908e+00 +5.4285548256237848e-01 +-3.1065901335219119e+00 +2.9450531539771979e-01 +4.4407743205132610e-01 +-2.6767233493312355e+00 +1.8225028950680899e+00 +5.5871500995799339e-01 +-3.0966786048671460e+00 +3.9808456873571829e-01 +4.5689936229120831e-01 +-2.6550732319633599e+00 +3.8946370993724599e-01 +4.6973844121421954e-01 +-2.6552549939784682e+00 +1.3313524766119433e+00 +-1.0202881311612932e-01 +-2.4407617549264908e+00 +1.3293369131106278e+00 +-9.4184834605808510e-02 +-2.4389971843918787e+00 +1.3293369131106278e+00 +-9.4184834605808510e-02 +-2.4389971843918787e+00 +3.1514787492504776e-01 +-6.1258019995624843e-02 +-2.5630409257512041e+00 +5.4706991409377836e-01 +-4.3968277905780048e-02 +-2.7010550629255596e+00 +5.4690760242648861e-01 +-3.8080692193807435e-02 +-2.7000939697032327e+00 +6.5096341267820068e-01 +-3.9072699639845054e-02 +-2.7957896761294059e+00 +6.2557723301713175e-01 +-3.7440090581400493e-02 +-2.7748435552262429e+00 +4.5890545585574344e-01 +-2.9852425758548691e-02 +-2.6543157651217872e+00 +4.3181927670242476e-01 +-2.4777176190713960e-02 +-2.6448789205556671e+00 +1.3143492640708885e+00 +-2.4172211525984033e-02 +-2.4304036386799202e+00 +1.3530023763424412e+00 +9.1995405487134332e-03 +-2.4985328139088208e+00 +1.3191940846325068e+00 +1.5341439543445773e-02 +-2.3986423803336985e+00 +6.1826546097453150e-01 +2.5477343473920576e-02 +-2.7713786932016906e+00 +5.3165124476072834e-01 +3.8672560976146450e-02 +-2.6890414575739063e+00 +1.5590663969031902e+00 +1.7266874549938378e-02 +-3.9259925289088597e+00 +3.4351026033994425e-01 +5.2156254527366254e-02 +-2.6527714619708678e+00 +4.2340057336390557e-01 +5.4908812428089489e-02 +-2.6479300506805514e+00 +1.4506073119425431e+00 +3.8450474403935460e-02 +-2.7294430910025107e+00 +6.1276797985102693e-01 +7.1956946643230782e-02 +-2.7681384965015452e+00 +6.1378582992757491e-01 +7.6123337852198714e-02 +-2.7637643877982394e+00 +6.9241402532721563e-01 +7.8984687447201343e-02 +-2.8419445947720288e+00 +6.1444599552115486e-01 +8.6261664965858104e-02 +-2.7674376289502023e+00 +4.5518980240191698e-01 +9.0923160116181789e-02 +-2.6574845994724323e+00 +7.3863955187027797e-01 +9.3180930177668764e-02 +-2.8794144127559673e+00 +8.2612121546625417e-01 +9.7711983658884102e-02 +-2.9739103915462715e+00 +6.2329002006339984e-01 +1.0313948917457155e-01 +-2.7722043261587972e+00 +3.4364015790591129e-01 +1.1694869322965444e-01 +-2.6571315484195721e+00 +6.4119312458702671e-01 +1.2833155148102912e-01 +-2.7954576053534410e+00 +2.2804897423683284e+00 +1.3197617957644109e-01 +-4.0448826591023987e+00 +3.0123365865112528e-01 +1.3507673672137280e-01 +-2.6647758826959365e+00 +1.4275816089285860e+00 +1.4271173055053549e-01 +-2.6967086346145548e+00 +5.2483382955243252e-01 +1.4837789633853879e-01 +-2.6891600542732399e+00 +5.7126786241197602e-01 +1.6180466501365182e-01 +-2.7269667741925243e+00 +5.7126786241197602e-01 +1.6180466501365182e-01 +-2.7269667741925243e+00 +3.2765698769576485e-01 +1.6825780289717562e-01 +-2.6617917935155746e+00 +5.5841276541803253e-01 +1.7584154189247012e-01 +-2.7197076120617423e+00 +5.1693960361815916e-01 +1.7841376016354635e-01 +-2.6879846151155302e+00 +5.6672303083825160e-01 +1.8115951110148190e-01 +-2.7246587961681588e+00 +4.7447610617937952e-01 +1.8001444701971855e-01 +-2.6667784116674524e+00 +2.2470060719996288e+00 +2.1117038502757285e-01 +-3.9511201553811142e+00 +2.2470060719996288e+00 +2.1117038502757285e-01 +-3.9511201553811142e+00 +4.7433829059461957e-01 +1.8413266545098958e-01 +-2.6702530887883311e+00 +3.5562173265863850e-01 +1.8664029983273078e-01 +-2.6578373118123189e+00 +6.0432353523154392e-01 +1.9663800880177820e-01 +-2.7613468964274919e+00 +1.3947006782547640e+00 +2.0092674816415057e-01 +-2.5930696016749533e+00 +8.0041911382448661e-01 +2.2170861858036253e-01 +-2.9453085790637252e+00 +1.3340815689701566e+00 +2.2505616995404962e-01 +-2.3980471272020218e+00 +1.0157881256045520e+00 +2.5963984183565231e-01 +-3.2100482597699096e+00 +5.1357272037399071e-01 +2.3933101602110921e-01 +-2.6838664943939747e+00 +7.8454679245702807e-01 +2.5801152047943743e-01 +-2.9318896682552440e+00 +6.9054888083893329e-01 +2.6200915766517963e-01 +-2.8389700842991434e+00 +3.6493302602527189e-01 +2.5151497925827110e-01 +-2.6507177681230849e+00 +1.3872247209370454e+00 +2.6557102107360658e-01 +-2.5876204810025785e+00 +4.9729355850727563e-01 +2.5609918304485213e-01 +-2.6747419497578875e+00 +3.7767028262214847e-01 +2.5586853482386479e-01 +-2.6516711375292865e+00 +4.1513370940300043e-01 +2.6012175566261631e-01 +-2.6531444497736700e+00 +5.2524119900381794e-01 +2.6691425824782022e-01 +-2.6886525205178460e+00 +5.1230571782837597e-01 +2.6704139735215565e-01 +-2.6823493020863127e+00 +4.0698849669011938e-01 +2.6645716202467096e-01 +-2.6683785231269805e+00 +5.0121595380680617e-01 +2.6923427588353671e-01 +-2.6660387562869174e+00 +4.9419973485088148e-01 +2.7751247302800602e-01 +-2.6702119667421846e+00 +1.7276874645947649e+00 +3.3449067072374228e-01 +-3.0999083814558679e+00 +5.4026371801238926e-01 +3.1385876540343405e-01 +-2.6983021672565179e+00 +2.2804030600927550e+00 +4.1986770136177698e-01 +-3.9059562156877212e+00 +2.3007803546089898e+00 +4.2851724172216277e-01 +-3.9368717829614912e+00 +2.2887074400869896e+00 +4.2724830648495771e-01 +-3.9063648002542428e+00 +2.2975238366977435e+00 +4.3515425977469346e-01 +-3.9285188590935642e+00 +2.2983073221801971e+00 +4.4177907130541705e-01 +-3.9217468898589276e+00 +9.1216583544372831e-01 +3.6933604227874828e-01 +-3.0939130675664446e+00 +5.1799226612664029e-01 +3.5879652183027094e-01 +-2.6941685077576967e+00 +5.0076377593455146e-01 +3.5895883453897148e-01 +-2.6813214435646868e+00 +5.0076377593455146e-01 +3.5895883453897148e-01 +-2.6813214435646868e+00 +4.4064726355650014e-01 +3.5693188327678432e-01 +-2.6624498065682669e+00 +4.5184735826918615e-01 +3.5847391000982104e-01 +-2.6626184660754175e+00 +4.4228992893869234e-01 +3.7607000798461437e-01 +-2.6541433478652974e+00 +4.1608712121906816e-01 +3.7938155533725204e-01 +-2.6465559471942135e+00 +2.6805103986367179e-01 +3.7929944716412234e-01 +-2.6946308896831930e+00 +2.4821956193646666e-01 +3.7886852768173573e-01 +-2.7002806201837277e+00 +3.4380213750382421e-01 +3.8070764402282875e-01 +-2.6579193052724723e+00 +2.1582828096307821e-01 +3.8092914002656486e-01 +-2.7295755189208690e+00 +2.5218619631089123e-01 +3.8193192061776959e-01 +-2.6970927232261461e+00 +2.3771776121221563e-01 +3.8225858995167883e-01 +-2.7054920971214376e+00 +3.5173694234207797e-01 +4.2247044324267624e-01 +-2.6627740453087969e+00 +2.8215626020467455e-01 +4.4945596198893334e-01 +-2.6959723274086334e+00 +1.8211523201145148e+00 +5.5829595257039322e-01 +-3.0962869747079091e+00 +1.8211523201145148e+00 +5.5829595257039322e-01 +-3.0962869747079091e+00 +2.6877502777587314e-01 +4.6149941806219424e-01 +-2.7403007015457477e+00 +1.9701989979109258e-01 +4.6198661613763614e-01 +-2.7575261267145272e+00 +2.8754531219094837e-01 +4.6289062020686306e-01 +-2.6861549432419167e+00 +2.8754531219094837e-01 +4.6289062020686306e-01 +-2.6861549432419167e+00 +1.3329653719833732e+00 +-6.8473463415719443e-02 +-2.4366353960469840e+00 +1.3187542082903945e+00 +-4.2881648239373120e-02 +-2.3524776503369114e+00 +1.3335029557150502e+00 +-3.9292916884286898e-02 +-2.3510426563325497e+00 +1.3513605715245312e+00 +-2.6694665790694370e-02 +-2.5074548398082714e+00 +1.3368857606273179e+00 +-1.8516340893116146e-02 +-2.4743630844018578e+00 +1.8255146030246259e+00 +-3.3791993622585038e-02 +-3.3117934665038975e+00 +1.8354166019985358e+00 +-2.5825790245115630e-02 +-3.3226582489588492e+00 +1.0301652210057501e+00 +3.7405898166431202e-03 +-3.2213766358179421e+00 +1.9458095895459311e+00 +9.9641335831481643e-04 +-3.5239696897832320e+00 +1.8292455520038831e+00 +7.7067179234346318e-03 +-3.3162945312206333e+00 +1.5793360489661010e+00 +1.1965126641390586e-02 +-3.9521956502886257e+00 +1.9518541611037377e+00 +1.8503233775198750e-02 +-3.5292078993826732e+00 +1.3254530347420217e+00 +5.1726492108284172e-02 +-2.4174264074951637e+00 +1.4216905093991470e+00 +5.5176168202194911e-02 +-2.6861857063625245e+00 +1.3477901144218409e+00 +6.1697317726216373e-02 +-2.5070050529992871e+00 +1.8286223415061920e+00 +5.0248493946459596e-02 +-3.3091089745397388e+00 +4.4087399940137784e-01 +7.5907023365701876e-02 +-2.6474610776679399e+00 +5.6467012326130850e-01 +7.4260826665134644e-02 +-2.7159515908856275e+00 +6.8478567912708899e-01 +7.4997697990069251e-02 +-2.8355516230787421e+00 +1.8759820915442216e+00 +6.3079195800056678e-02 +-3.4199617236716793e+00 +6.5035664398985604e-01 +8.1080593069467716e-02 +-2.8003638741925170e+00 +1.8238704266280741e+00 +6.9430421119121233e-02 +-3.3221527108820443e+00 +6.4311691212791844e-01 +9.4448223500134404e-02 +-2.7904767223766753e+00 +1.9202317539375335e+00 +1.2115947212808800e-01 +-3.4796562242750175e+00 +1.7986130098964599e+00 +1.2388279870516899e-01 +-3.2561464237303572e+00 +1.3876413910368970e+00 +1.2780030820311711e-01 +-2.5973896888834660e+00 +1.0255195168446314e+00 +1.3418800183289281e-01 +-3.2043555841041824e+00 +5.3509884895087800e-01 +1.3665816162612060e-01 +-2.6984412579560719e+00 +1.4598140689350914e+00 +1.3908203682751324e-01 +-2.7493702840744185e+00 +1.3902898059785773e+00 +1.4078008267782918e-01 +-2.5754732429964311e+00 +5.1610911425753470e-01 +1.4485767150488377e-01 +-2.6809531611447959e+00 +5.2335116381529689e-01 +1.5449775831250687e-01 +-2.6856067863271393e+00 +1.3419281887862218e+00 +1.5387795408137264e-01 +-2.4919405121697924e+00 +5.5530960100791904e-01 +1.6240297433261677e-01 +-2.7118175000338445e+00 +4.0446128140782128e-01 +1.7821264389424901e-01 +-2.6514057135594395e+00 +4.0449042615931458e-01 +1.7827731217419260e-01 +-2.6517684264033536e+00 +1.4594875604762618e+00 +1.8767652982257479e-01 +-2.7704764905863772e+00 +1.3142652087461955e+00 +1.8327034056489741e-01 +-2.4280199869751957e+00 +8.0877873168816117e-01 +1.9459621103069197e-01 +-2.9533959158379273e+00 +9.7864761307911579e+00 +5.4076832311678946e-01 +-1.5366441329519837e+01 +7.8575756013912701e-01 +2.1565873015430664e-01 +-2.9290959162177015e+00 +6.0397921137280686e-01 +2.1061451597068534e-01 +-2.7584769696685587e+00 +1.3358075568979009e+00 +2.1043147445986801e-01 +-2.4119750242792977e+00 +1.0218879677369987e+00 +2.5839130137154559e-01 +-3.2039282396385635e+00 +1.3301178049632056e+00 +2.5204737795053039e-01 +-2.4161736239082439e+00 +4.9169005743330785e-01 +2.5581703893373869e-01 +-2.6761110725448489e+00 +3.3573923101792541e-01 +2.5869387754994649e-01 +-2.6635423809322560e+00 +4.0751359148067146e-01 +2.6891230169317071e-01 +-2.6626223317619191e+00 +1.3395708544085920e+00 +2.8016064657728040e-01 +-2.3520388181009682e+00 +4.5413018670376271e-01 +3.1794181241400737e-01 +-2.6562218403530427e+00 +9.1126671409847482e-01 +3.5168108576095314e-01 +-3.0874914208614057e+00 +1.7615444682516659e+00 +3.8631656870435721e-01 +-3.1744264908037314e+00 +2.2995074532553597e+00 +4.4032599119417004e-01 +-3.9044930323052247e+00 +1.7630978709440734e+00 +3.9423475460027191e-01 +-3.1730219421897350e+00 +1.0024575727244596e+00 +3.9852369577750801e-01 +-3.3503724613090635e+00 +4.5142764830417842e-01 +3.4948920306456793e-01 +-2.6614318958480978e+00 +4.4700063584784450e-01 +3.6150721588809970e-01 +-2.6610091127523359e+00 +2.2844785510696500e-01 +3.5962433210234546e-01 +-2.7321869263440575e+00 +4.6569938323421090e-01 +3.7855166255811284e-01 +-2.6634304801791244e+00 +4.3638667680075777e-01 +3.7905425411179949e-01 +-2.6535962017888624e+00 +1.7990659238111129e-01 +3.7745606818423161e-01 +-2.7728074685964121e+00 +3.5316092645948527e-01 +3.8051949365751725e-01 +-2.6560022200499502e+00 +1.8414961858383565e+00 +5.3926109029967650e-01 +-3.0776519323749993e+00 +4.7185717161824853e-01 +4.5442492886225744e-01 +-2.6931931731410343e+00 +2.0930636430518212e-01 +4.4943151966737432e-01 +-2.7441396827827340e+00 +1.8185912533169646e+00 +5.5378031655238136e-01 +-3.0910875764716570e+00 +2.5710069374292122e-01 +4.6116208274150744e-01 +-2.7447670391832726e+00 +1.0872414522979916e+00 +-8.7597771489721241e-02 +-3.2825610802042031e+00 +6.0745487440332457e-01 +-4.2788262774002980e-02 +-2.7624869249635711e+00 +5.9808659547425624e-01 +-3.7591682485357950e-02 +-2.7524356239008942e+00 +1.3351299128602261e+00 +-3.5365333020136072e-02 +-2.4378076073557855e+00 +1.3270922113579913e+00 +2.1588039784379440e-02 +-2.4068703575890278e+00 +5.8255592711019988e-01 +3.4726729034282172e-02 +-2.7430085841208420e+00 +1.8334486722768393e+00 +1.0872307413065269e-02 +-3.3103730580782624e+00 +1.8083286346147585e+00 +1.4807855552561568e-02 +-3.2663172989494584e+00 +1.8083286346147585e+00 +1.4807855552561568e-02 +-3.2663172989494584e+00 +1.9569679988902089e+00 +1.3106361751732442e-02 +-3.5370553401082621e+00 +6.0689520217993431e-01 +7.8554846751966209e-02 +-2.7609109196299375e+00 +1.3222289292852463e+00 +9.0885634640893956e-02 +-2.4302248450248203e+00 +7.8172084476778991e-01 +9.6555619814713251e-02 +-2.9253359184956369e+00 +5.8561399959778349e-01 +1.4282722298797998e-01 +-2.7440596990620034e+00 +7.8187079835656026e-01 +1.4778192406322005e-01 +-2.9293768621071896e+00 +1.5112921614085446e+00 +1.6092194351305339e-01 +-2.8435619105184404e+00 +4.7555074445300261e-01 +1.7036876395261483e-01 +-2.6685615897193440e+00 +6.0912431584760596e-01 +1.7183522649559130e-01 +-2.7679682328873536e+00 +7.7826257791789144e-01 +1.8287890798150366e-01 +-2.9817099643617913e+00 +2.2429927705897947e+00 +2.1515845653060087e-01 +-3.9528149203597929e+00 +1.3259461966525441e+00 +2.3400388019057791e-01 +-2.3858422954039149e+00 +5.7306960107788785e-01 +2.3588669181614791e-01 +-2.7250626524167543e+00 +1.3250317064049746e+00 +2.5280769603544212e-01 +-2.4533730191400860e+00 +1.3280584445700545e+00 +2.5483998409911285e-01 +-2.3824076716233575e+00 +5.0611328377847054e-01 +2.5470543404454210e-01 +-2.6813467926439265e+00 +1.7306191022769775e+00 +3.2510785662374597e-01 +-3.1075427827151501e+00 +4.4236723952741991e-01 +2.8709681266025866e-01 +-2.6434269296809152e+00 +1.3537664724512188e+00 +2.9918392733168314e-01 +-2.3565083086833014e+00 +4.7721827806530076e-01 +4.0566991813873149e-01 +-2.6742551925108247e+00 +4.2581244240850236e-01 +5.4052513504701594e-01 +-2.8168274761305194e+00 +1.6271745864084266e+00 +-1.4736246244819728e-01 +-4.0041716636645512e+00 +5.6898161647257373e-01 +-5.3267035665064320e-02 +-2.7232494580624205e+00 +6.1428268812560627e-01 +-5.2938004831802485e-02 +-2.7687008256062033e+00 +6.0537321072183037e-01 +-3.6509297907860803e-02 +-2.7600994994767460e+00 +5.4921308823277759e-01 +-2.6781171709037512e-02 +-2.7009082214128028e+00 +1.3250604855376469e+00 +-9.8766606542088700e-03 +-2.3898517994795867e+00 +1.8951854118400349e+00 +-3.9930481662816833e-02 +-3.4447413113055840e+00 +1.3340424930167565e+00 +6.6194947429125142e-02 +-2.3758656390565842e+00 +1.8591611474077983e+00 +7.0542074121684215e-02 +-3.3832580634413909e+00 +7.8235456274282655e-01 +1.1791180873969012e-01 +-2.9290215148159082e+00 +6.1333024196508346e-01 +1.3149357646106422e-01 +-2.7660691976129965e+00 +1.7072757584520111e+00 +1.6047013641248176e-01 +-4.1213334173146956e+00 +1.3312799401516113e+00 +1.5025318680392788e-01 +-2.4199252898175492e+00 +7.2595162145725722e-01 +1.8258240473649420e-01 +-2.8882711015205431e+00 +7.2810173576446469e-01 +1.9551535676029394e-01 +-2.8872503430089544e+00 +1.7741741404782549e+00 +2.1662923497334755e-01 +-3.2223466115100545e+00 +1.3353102753872457e+00 +2.1055106155394743e-01 +-2.4750130610870142e+00 +1.0231452775036807e+00 +2.2661680861374967e-01 +-3.2138338080446198e+00 +5.6233509596088105e-01 +2.1235731024615750e-01 +-2.7205301458000957e+00 +6.4404351735958909e-01 +2.2923744506755597e-01 +-2.7970373588644257e+00 +1.3237638840946206e+00 +2.4823485827774419e-01 +-2.4149878244397458e+00 +6.4253260318735761e-01 +2.5507069773075375e-01 +-2.7867989306377789e+00 +1.3242431284416567e+00 +2.6661332644843627e-01 +-2.4770961734141816e+00 +5.6001217330170794e-01 +2.8205524908281859e-01 +-2.6972355336280920e+00 +5.3178488475058006e-01 +3.3414683719636412e-01 +-2.6981663898717136e+00 +1.8137960827117332e+00 +4.4060059090332371e-01 +-3.2182351044994277e+00 +1.7836587741448919e+00 +5.4003368540880714e-01 +-4.5135519735775524e+00 +1.7836587741448919e+00 +5.4003368540880714e-01 +-4.5135519735775524e+00 +1.8465225480502809e+00 +5.3988101950030620e-01 +-3.2251111445554730e+00 +1.8465225480502809e+00 +5.3988101950030620e-01 +-3.2251111445554730e+00 +5.2555754857914705e-01 +3.2105658531324649e-01 +-2.6975465026537808e+00 +1.3869882070344983e+00 +-1.9792493097404867e-02 +-2.6027246442596872e+00 +8.7065776024582331e-01 +2.6165818083081022e-01 +-3.0192713947412528e+00 +1.3907745275701304e+00 +-1.2616818399813451e-01 +-2.5944425835283740e+00 +1.3905558087259315e+00 +-1.0720612980703642e-01 +-2.5943557529893093e+00 +1.3170003060790159e+00 +-2.8812326364598115e-02 +-2.3557349954808458e+00 +8.9244621319512174e-01 +1.8854105079438657e-01 +-3.0658891123503147e+00 +5.6570709467191127e-01 +1.8081599332049803e-01 +-2.7246867831750814e+00 +1.8307636746156932e+00 +2.8095762418401837e-01 +-4.4216359506870049e+00 +1.3370910476891911e+00 +1.7787292461575840e-01 +-2.3526850287433643e+00 +9.9807101903890727e-01 +2.6225259794084466e-01 +-3.1967974585042338e+00 +5.6819945509691239e-01 +-1.1221578639875864e-01 +-1.8944328916902355e+00 +6.3899552754518818e-01 +-9.7266005101666067e-02 +-2.7797474141616516e+00 +4.5158835692093122e+00 +-1.0428569874600781e-01 +-8.5515413263635676e+00 +4.5158835692093122e+00 +-1.0428569874600781e-01 +-8.5515413263635676e+00 +7.2138301680298766e-01 +1.7119991992355235e-01 +-2.8895385405059364e+00 +1.3317365055029364e+00 +1.6055729402267174e-01 +-2.3581150776767892e+00 +1.3735275903028350e+00 +2.6456447671779409e-01 +-2.5946149638215710e+00 +5.2085222361431971e-01 +3.7441363958691970e-01 +-2.6898963277868044e+00 +1.6169151051669359e+00 +-1.7343014220285860e-01 +-3.9814257516079263e+00 +1.6169151051669359e+00 +-1.7343014220285860e-01 +-3.9814257516079263e+00 +4.4194370352950312e+00 +-9.8007450053660711e-02 +-8.4360005442791799e+00 +4.4772049218956038e+00 +-8.4375916021111969e-02 +-8.5048014195880679e+00 +5.6432905706687375e-01 +-5.1937453258406867e-02 +-1.9059947964053807e+00 +4.8581815298673554e+00 +-6.4929723149131854e-02 +-8.9490337775927102e+00 +1.3882303343007660e+00 +7.2432255691960504e-02 +-2.5973318634110201e+00 +1.3373875480967192e+00 +9.2930456334065631e-02 +-2.3512025978005116e+00 +1.3389793662276359e+00 +9.3364617479676282e-02 +-2.3524841521646254e+00 +7.2196559692728768e-01 +1.9694127161536878e-01 +-2.8897217506564230e+00 +7.9643898080412068e-01 +2.3680152575050400e-01 +-2.9436856640196591e+00 +1.3292560086960494e+00 +2.2337488408014466e-01 +-2.4127200245215206e+00 +1.3439856407959550e+00 +2.5878856936063377e-01 +-2.3496433234686855e+00 +5.4323709793225328e-01 +2.6054730294491463e-01 +-2.7064488384174794e+00 +5.6369925334230575e-01 +-1.4496637949259786e-01 +-1.8941579157268629e+00 +1.3199347932637822e+00 +-1.6742296916212887e-01 +-2.4258703820685859e+00 +5.7426642190750299e-01 +-1.0077628247077375e-01 +-1.8945090247301499e+00 +5.7087584742833564e-01 +-9.8955493630526095e-02 +-1.8970476994093526e+00 +6.5696128640449580e-01 +-9.6994850049915121e-02 +-2.7922341575628331e+00 +4.5141458122782447e+00 +-7.5243725318962409e-02 +-8.5376863845921207e+00 +4.4665179343851689e+00 +-6.6356313618183879e-02 +-8.4996507245882178e+00 +1.5770988521923808e+00 +1.1434151240947215e-02 +-3.9497322647102617e+00 +1.3825902275161268e+00 +2.4561123195276624e-01 +-2.5997758057543994e+00 +1.3825902275161268e+00 +2.4561123195276624e-01 +-2.5997758057543994e+00 +1.3581880257372814e+00 +3.0838796478356617e-01 +-2.4463061931297534e+00 +4.4869183475853380e-01 +3.3689498417246305e-01 +-2.6591238073224641e+00 +5.7724756512767472e-01 +-6.3190358442410596e-02 +-1.8945446737954952e+00 +4.3804824155181761e+00 +-1.4529317254915841e-01 +-8.3721590454252599e+00 +4.6314185691260201e+00 +-1.1039561144005976e-01 +-8.6553182456148772e+00 +7.2607965465986057e-01 +-4.3579150973959854e-02 +-2.8780759142087811e+00 +1.3312163841461588e+00 +-1.9647984709795379e-02 +-2.3523971188969948e+00 +1.3189833770073420e+00 +6.7183936180335732e-02 +-2.4167858428582223e+00 +1.3362293849374804e+00 +6.8859867542126210e-02 +-2.3492085626058410e+00 +1.8469026851487660e+00 +2.6106838279214967e-01 +-4.4403153664677131e+00 +1.3295647761920739e+00 +1.9188764169662317e-01 +-2.3409699075329553e+00 +1.3255049204514624e+00 +2.4918304594213597e-01 +-2.3889881863490219e+00 +7.8258078630507200e-01 +3.0732167779934394e-01 +-2.9396674727861969e+00 +7.8258078630507200e-01 +3.0732167779934394e-01 +-2.9396674727861969e+00 +4.5585487897379924e+00 +-1.2867615574820915e-01 +-8.5708947771908619e+00 +4.6647531056501510e+00 +-1.2644745632963429e-02 +-8.6918915089613797e+00 +1.8117325475832498e+00 +5.5038974964175413e-01 +-4.5904656172842406e+00 +1.8994420529073568e+00 +5.3445693785190307e-01 +-3.0381417980891485e+00 +4.6550227817910637e+00 +-1.1439203463944492e-01 +-8.6763025391216626e+00 +9.2149470202847850e-01 +1.8455678138470422e-01 +-3.0862369095993460e+00 +5.8368722075355461e-01 +2.5412859899380980e-01 +-2.7472426369447902e+00 +-1.4618218781674600e-01 +6.1025030049147522e-01 +-3.7378656727223039e+00 +5.8081719493084460e-01 +1.2040630934078229e-01 +-2.7324968833647341e+00 +5.3354165686024080e-01 +3.1009579004257726e-01 +-2.6995789866480120e+00 +-2.3593729435464361e-01 +5.6243261769205732e-01 +-3.7252781664163082e+00 +4.9454416746139751e-01 +9.9288115071576047e-02 +-2.6747812394016832e+00 +5.3070425351549422e-01 +1.1700728309491767e-01 +-2.6865942338359718e+00 +-9.0423182305865224e-01 +1.7470227808424521e-01 +-1.9806252822017507e+00 +-9.6808956993727402e-01 +2.4726721380357466e-01 +-2.4532588172444583e+00 +5.7562736994145192e-01 +2.1921683275154447e-01 +-2.6976484539710262e+00 +1.2261426469970866e+00 +3.0261824443664970e-01 +-3.5897637643035085e+00 +4.4397160910912342e-01 +3.9605748518879730e-01 +-2.6724036643036833e+00 +-1.9136647556636457e-01 +5.4863302352835153e-01 +-3.6660899513339920e+00 +-7.0881043645981731e-02 +6.4721845380060739e-01 +-3.7720785697151982e+00 +-8.3562284410355891e-01 +6.1774788520406076e-01 +-2.5452502986292136e+00 +-8.7931396334819389e-01 +9.6671026459573789e-02 +-2.4750297920736615e+00 +-8.2814111918562239e-01 +1.0621702770408589e-01 +-2.5673604725136725e+00 +-8.2731910687652921e-01 +1.0739657973846767e-01 +-2.5579069538736183e+00 +-8.6517938932797789e-01 +1.0881989929694037e-01 +-2.5285880023096610e+00 +-9.7030554338491781e-01 +1.1601568494989725e-01 +-2.4467814554616245e+00 +-1.2258833599139634e+00 +1.2041388625200999e-01 +-2.3575538429345930e+00 +-1.2258833599139634e+00 +1.2041388625200999e-01 +-2.3575538429345930e+00 +-8.2756716959213250e-01 +1.4750220197438596e-01 +-2.5693233599798151e+00 +-9.1347964337583898e-01 +1.5065998832574198e-01 +-3.0858277957448994e+00 +-7.9681417328193049e-01 +1.7890781721346130e-01 +-2.5890988536796140e+00 +1.0389656395693005e+00 +2.8894199204308035e-01 +-3.3189226443769906e+00 +3.5684776360199061e-01 +2.8044350154266401e-01 +-2.6578990372491380e+00 +4.8376256994435440e-01 +3.9151305700395184e-01 +-2.6648302156696819e+00 +-1.6838909872419919e-01 +6.2084347362902959e-01 +-3.7273663063504410e+00 +-8.7680661370608437e-01 +4.6740181030892704e-02 +-2.4914923817666175e+00 +-9.7246841214869428e-01 +9.4980070228687485e-02 +-2.4423971999102356e+00 +1.6008365550923802e+00 +3.5324638539855638e-02 +-4.0394324227622178e+00 +1.7344356474445193e+00 +5.7783921074542138e-02 +-4.1775681713911146e+00 +1.6344062317070549e+00 +1.1275236279992042e-01 +-4.0619081078550803e+00 +1.5906493212391593e+00 +1.1476353214494292e-01 +-4.0117267608176927e+00 +-1.2319887488580523e+00 +1.6152238107579431e-01 +-2.3752719575449088e+00 +1.1809859330421786e+00 +1.6871106737772687e-01 +-3.4452957688268531e+00 +1.0642066231940952e+00 +1.8829693864724650e-01 +-3.2681018005889779e+00 +5.3866363439549636e-01 +2.4213531968797403e-01 +-2.6956099801885767e+00 +-7.7660536267228264e-01 +3.6279445570997576e-01 +-2.6333998820030620e+00 +-7.7616657037125469e-01 +3.6380121636446783e-01 +-2.6265830192492254e+00 +-8.7787787637899584e-01 +4.3731359313942936e-01 +-3.0816597683837772e+00 +-3.8568970264987967e-01 +4.7187811848830202e-01 +-3.9640383968522395e+00 +-1.6726044295243186e-01 +6.5242558118903704e-01 +-3.7431465182765624e+00 +-1.2697654112636387e+00 +7.6121699844728857e-02 +-2.3736198107001796e+00 +-8.2355419193795654e-01 +8.9119962136181841e-02 +-2.5591576931654680e+00 +-1.2176568639512397e+00 +1.0175205093284651e-01 +-2.3315352932120188e+00 +1.5554848050165477e+00 +9.9393615583416223e-02 +-3.9782870516218720e+00 +1.5554848050165477e+00 +9.9393615583416223e-02 +-3.9782870516218720e+00 +-7.5490606037681729e-01 +1.5242345986715292e-01 +-2.6634175503186177e+00 +-7.9179296370057572e-01 +1.7125292542338533e-01 +-3.0037364913014128e+00 +1.1421489440081731e+00 +1.6935800245267521e-01 +-3.3921331885110741e+00 +6.0311649421485114e-01 +2.0152390014471505e-01 +-2.7537743779366659e+00 +4.7051900484408010e-01 +2.4579638276699659e-01 +-2.6680998280381552e+00 +-2.2226466045937557e-01 +4.3785942247724424e-01 +-3.7084111168507938e+00 +-3.6310453478121579e-01 +4.6795389593513764e-01 +-3.9092173890887110e+00 +-3.6310453478121579e-01 +4.6795389593513764e-01 +-3.9092173890887110e+00 +-7.4671768660020177e-01 +4.0183131223987112e-01 +-2.6655618247509456e+00 +-8.6780352169359209e-01 +3.9635464634262535e-01 +-2.5024778916171559e+00 +-3.2688067924453917e-01 +4.7171644471006802e-01 +-3.8449876896113406e+00 +-3.2703760631296069e-01 +4.7214399524767553e-01 +-3.8401897268850935e+00 +-2.9040137929572635e-01 +4.7438859161211572e-01 +-3.7661826881412210e+00 +-4.4055692151769754e-01 +5.1054281360325970e-01 +-4.1314819014779554e+00 +-4.4055692151769754e-01 +5.1054281360325970e-01 +-4.1314819014779554e+00 +-9.2245842410450685e-01 +4.1280476458542070e-01 +-2.4753672864319647e+00 +-4.0099845874192513e-01 +5.1491733720077126e-01 +-4.0536475759210964e+00 +-1.6255533094718638e-01 +5.0468438234929203e-01 +-3.5781722782758627e+00 +-1.5908276511374930e-01 +5.5778536436008730e-01 +-3.6328743571075992e+00 +-9.7214554057965397e-01 +5.0967344593968633e-01 +-2.4394484597317176e+00 +-1.0190017463082129e-01 +6.5059642744638491e-01 +-3.7619486311561889e+00 +1.0236579999314539e+00 +2.6973399085695265e-02 +-3.2097253005533180e+00 +9.3710948654872239e-01 +3.8622408853775554e-02 +-3.0994808578999025e+00 +1.6944086350804828e+00 +1.5396228444738777e-02 +-4.1485967674872724e+00 +5.0570456138660713e-01 +5.7488566838039212e-02 +-2.6577336665030407e+00 +-1.2654085586659860e+00 +1.0008819397218681e-01 +-2.3732366507881046e+00 +5.3535915402394152e-01 +6.6695096363746778e-02 +-2.6523402126298778e+00 +5.1243245005048388e-01 +7.7086953432291272e-02 +-2.6681356839708572e+00 +1.1129767508763908e+00 +6.4141737395125770e-02 +-3.3417416160692910e+00 +4.0102565510354909e-01 +8.1957295894695206e-02 +-2.6211745325275033e+00 +1.5564284572607869e+00 +5.5717427663294655e-02 +-3.9638012844328174e+00 +8.0119452082763942e-01 +9.4262508941937426e-02 +-2.9454536899649137e+00 +4.2428237320601020e-01 +1.2099762579182552e-01 +-2.6282230447382524e+00 +-7.9100436468537438e-01 +1.5288232147795577e-01 +-2.6004852696729173e+00 +-7.9361721907367722e-01 +1.6389236298155019e-01 +-2.5834457138361513e+00 +5.9374202658579345e-01 +1.7097431843192701e-01 +-2.7458744875494188e+00 +6.2191732011241674e-01 +1.9443491026440518e-01 +-2.7858584440354615e+00 +4.1873947087258845e-01 +2.6630509668990876e-01 +-2.6393447166857298e+00 +-3.0930801449882911e-01 +4.4421316670445310e-01 +-3.8106452962736421e+00 +-3.3804998792741264e-01 +4.6194063139023195e-01 +-3.6005171455959664e+00 +-3.4532200419113329e-01 +4.7663250834975018e-01 +-3.8792264221527977e+00 +-8.0763533436795443e-01 +4.0575555922578094e-01 +-2.5772568666856968e+00 +-4.1977830296587210e-01 +5.1887664514520315e-01 +-4.0737355903286971e+00 +-4.1977830296587210e-01 +5.1887664514520315e-01 +-4.0737355903286971e+00 +-1.4748949399814248e-01 +5.3215352173975361e-01 +-3.5770299284668217e+00 +-2.7468951371524197e-01 +5.6938325226178044e-01 +-3.7650234645551790e+00 +-3.0879535129303676e-01 +5.8347179010517680e-01 +-3.8107921837214302e+00 +-1.5272758852470777e-01 +5.9939122709753745e-01 +-3.7373683207326978e+00 +-7.3647301296685030e-01 +5.7168416506887754e-01 +-2.6997185336345075e+00 +-7.4611253723983062e-01 +5.7775465338996501e-01 +-2.6839540977124576e+00 +-8.5543936246822427e-01 +5.6635689278498402e-01 +-2.5393548175172107e+00 +-7.6025706854853137e-01 +6.5010366603212510e-01 +-2.6649048087965115e+00 +-8.6400340798061503e-01 +9.9002558497654353e-02 +-2.7370575030265720e+00 +-8.6400340798061503e-01 +9.9002558497654353e-02 +-2.7370575030265720e+00 +6.2277999417119612e-01 +1.0443214987366620e-01 +-2.7605036051990566e+00 +9.9871552680652942e-01 +1.0243602328916836e-01 +-3.1999346565738644e+00 +-8.8013665047307521e-01 +1.6823129166982709e-01 +-2.4913116201030894e+00 +-1.1814276767789207e+00 +1.8401133914366286e-01 +-2.3766153913302115e+00 +1.0250338196198840e+00 +1.7024464865085756e-01 +-3.2143838519018266e+00 +5.6575771771043926e-01 +1.9947453731899109e-01 +-2.7190832754880314e+00 +5.6591991561879229e-01 +2.1838757721005120e-01 +-2.7203428882378682e+00 +9.0695636644037203e-01 +2.9066217304789388e-01 +-3.0847885706046010e+00 +5.4139344435224035e-01 +3.1362225452066289e-01 +-2.7149355143991358e+00 +6.0449345576329905e-01 +3.4090373263973978e-01 +-2.7709108189913794e+00 +-8.0765510748734270e-01 +3.8238086162721130e-01 +-2.5802032662678442e+00 +-4.4137117718471641e-01 +4.7527743388911636e-01 +-4.0867586404171110e+00 +-1.9229547047288764e-01 +4.6273342229962316e-01 +-3.5560797932881600e+00 +4.1081745460734037e-01 +4.0157735245539106e-01 +-2.6562471985455947e+00 +-7.1767200901496286e-01 +4.4915218446235922e-01 +-2.7376190159233427e+00 +-2.1180520252621601e-01 +5.2716974811575290e-01 +-3.7153105987442059e+00 +-2.2410070390060322e-01 +5.4088900085504765e-01 +-3.7135763973691285e+00 +-2.0692679063459568e-01 +5.5006198024038233e-01 +-3.7018159158089170e+00 +4.1588948442096330e-01 +4.5842091625172587e-01 +-2.6109684078638371e+00 +-7.7829050867912919e-01 +5.8078428540260152e-01 +-2.6188215575693001e+00 +-7.2647141953541650e-01 +6.1186563163386665e-01 +-2.7012323984390605e+00 +-7.9443977916992137e-01 +6.1705343551717173e-01 +-2.5861193457321625e+00 +-8.0708351346954244e-01 +6.4148348782432962e-01 +-2.5920026719098619e+00 +-1.2253339815791822e+00 +2.2023356302931060e-02 +-2.3708620348083724e+00 +-8.4442538041587589e-01 +8.5085223375850165e-03 +-2.5419322044199872e+00 +-1.1730582258354842e+00 +3.4848638824931874e-02 +-2.3648137385987815e+00 +-8.6211802117214253e-01 +3.4172512799144794e-02 +-2.5251606970270046e+00 +-9.9970443579050638e-01 +4.0528249920783403e-02 +-2.3970521975824921e+00 +-1.2978088388680606e+00 +6.5974651858144648e-02 +-2.3852287300217649e+00 +1.1037329098005269e+00 +1.5299110874462165e-02 +-3.3179988372903213e+00 +5.8289164709167529e-01 +4.3519650346475085e-02 +-2.7132722072514253e+00 +-1.0198665998041141e+00 +8.3353053063848215e-02 +-2.4143803786349434e+00 +-1.3055490422385896e+00 +9.6839527891226365e-02 +-2.3906754555842507e+00 +1.6721390314099867e+00 +2.9262289078628920e-02 +-4.1153373383979597e+00 +7.7957986192340545e-01 +6.4952686397526466e-02 +-2.9236802131012047e+00 +5.8809549634984049e-01 +7.3934584470826153e-02 +-2.7237101420946987e+00 +4.0012740519288209e-01 +8.6250622067264845e-02 +-2.6673491210313753e+00 +1.3466612692520834e+00 +9.5142330984566523e-02 +-3.6569864461929948e+00 +7.7964792762524360e-01 +1.1450139448438865e-01 +-2.9177255827468831e+00 +5.2059957676165614e-01 +1.5225154444489247e-01 +-2.6693966541036658e+00 +5.7029668074597617e-01 +1.5428374093670263e-01 +-2.7288828561569591e+00 +1.5687936295376130e+00 +1.5734264296448183e-01 +-3.9977970915353449e+00 +3.4565392748521778e-01 +1.6670512216138958e-01 +-2.6122151975458854e+00 +-9.3388385603111612e-01 +2.1192256069860360e-01 +-2.4646273427914323e+00 +6.8981003277684805e-01 +1.8656707286916774e-01 +-2.8406897186311006e+00 +-9.7683556516294934e-01 +2.2478133049172921e-01 +-2.4489647920133679e+00 +6.5546735284411162e-01 +2.1539657657347142e-01 +-2.8133170170731985e+00 +1.1985596323746099e+00 +2.3270590357666157e-01 +-3.4545152561285031e+00 +-9.4947668833379406e-01 +2.9219284296364151e-01 +-2.4549054000396135e+00 +9.4882870036522549e-01 +2.8240602716917657e-01 +-3.1175946989651626e+00 +-8.3437915720690081e-01 +3.0970348647452578e-01 +-2.5407501954219014e+00 +6.4630309083932802e-01 +3.0188192555411320e-01 +-2.8089746254390153e+00 +9.6372360668701451e-01 +3.1519610162693323e-01 +-3.1513770453772767e+00 +-7.9371434064011492e-01 +3.7478080474450998e-01 +-2.5900678696740527e+00 +-2.3607854189086250e-01 +4.4717414058597377e-01 +-3.6991552528052343e+00 +-1.7655897539779752e-01 +4.3415183245448769e-01 +-3.5165440884113028e+00 +-8.7108073802917296e-01 +4.5084060710245888e-01 +-3.0901044649304725e+00 +-3.9660986448053648e-01 +4.9532315793392362e-01 +-4.0081625206836362e+00 +-3.9660986448053648e-01 +4.9532315793392362e-01 +-4.0081625206836362e+00 +-2.7624699210351972e-01 +4.8941508856609195e-01 +-3.7466644470009305e+00 +-3.1246279634784158e-01 +5.0322805409734539e-01 +-3.8175906520277820e+00 +-2.6339950282206687e-01 +5.0716643687428475e-01 +-3.7095883853400542e+00 +-2.8716934678641021e-01 +5.1494273962083081e-01 +-3.7679395419556978e+00 +-8.1177548622493911e-01 +4.6112622550529786e-01 +-2.5809313620899843e+00 +-8.8658845353798876e-01 +4.5807320545788377e-01 +-2.4972281643537197e+00 +4.4872988137124364e-01 +4.3295789560253184e-01 +-2.6519023984366710e+00 +-2.8837402219405733e-01 +5.6212795755911193e-01 +-3.7733321148982886e+00 +3.8295505373374772e-01 +4.5120214502330991e-01 +-2.6512574235752360e+00 +-7.7446812495883366e-01 +4.9995882620142645e-01 +-2.6139817950397997e+00 +-1.9239109887684075e-01 +6.0224741225905487e-01 +-3.7217033878613575e+00 +-6.9283045848240840e-02 +6.3622181636664565e-01 +-3.7572725925200796e+00 +-7.6514436780175332e-02 +6.4236928609890065e-01 +-3.7664249888701060e+00 +-7.9582163564638916e-02 +6.6836995452953107e-01 +-3.7723069091704367e+00 +-7.8174174543460473e-01 +5.7310292467642687e-01 +-2.5784702868134968e+00 +-8.2781485679626154e-01 +6.1055383195423973e-01 +-2.5593932566119935e+00 +-7.1208046353696730e-01 +6.4675527716606640e-01 +-2.7759934819185017e+00 +-8.9045120871928474e-01 +6.2170756686001549e-01 +-2.4993923478685054e+00 +-9.0432964093826973e-01 +6.2232199798316223e-01 +-2.4867876144845416e+00 +-8.5598578793639601e-01 +7.8666103543414273e-03 +-2.5378778100620041e+00 +-9.5203537607664357e-01 +5.6355306214050764e-02 +-2.4435404078114602e+00 +1.1995724608686698e+00 +2.4759271696091822e-02 +-3.4471999797039503e+00 +-1.0531821666954424e+00 +8.4614094400075099e-02 +-2.3979429508933170e+00 +1.0689564891029617e+00 +3.4238509786840080e-02 +-3.2663034922432459e+00 +7.8283345844480201e-01 +4.9018028074786481e-02 +-2.9312183317008405e+00 +5.9678834709082107e-01 +7.6695654901033347e-02 +-2.7417001382006143e+00 +5.5781005006945528e-01 +7.9303318423753405e-02 +-2.7045733337173057e+00 +5.0202572727244754e-01 +8.1170317083369969e-02 +-2.6640924135306792e+00 +7.0290481127220850e-01 +8.8460278272551568e-02 +-2.8316454208013160e+00 +9.7718605229049216e-01 +9.1324457498149728e-02 +-3.1775198130858358e+00 +-7.7105626909212055e-01 +1.5807628725108322e-01 +-2.6464028329098470e+00 +-8.0244553111080297e-01 +1.6551345549589230e-01 +-2.5827024825147000e+00 +5.8561703091864881e-01 +1.5437690519639974e-01 +-2.7418578024010336e+00 +7.6897074532974952e-01 +1.7656729946277167e-01 +-2.9315560791126596e+00 +-8.4645890708976690e-01 +2.0975332794555776e-01 +-2.5306903761010524e+00 +-9.6660847685333151e-01 +2.1293701457419331e-01 +-2.4479534793502564e+00 +4.2142950959279102e-01 +1.8538308829350400e-01 +-2.6249021375348063e+00 +4.0333033805285723e-01 +1.8487939032279044e-01 +-2.6248384791281687e+00 +-1.0607993920892846e+00 +2.2199664476629691e-01 +-2.4019116453334566e+00 +-1.1284865457112505e+00 +2.3408479653857556e-01 +-2.3729287498631910e+00 +6.1334401404666616e-01 +2.0977431635129765e-01 +-2.7490497099096540e+00 +6.3472391073310663e-01 +2.3618574560554517e-01 +-2.7839831554083796e+00 +-7.7232141479549010e-01 +2.7249668104694796e-01 +-2.6360146887082503e+00 +-8.9856517068654296e-01 +3.0326983030555887e-01 +-3.0834650740620853e+00 +5.5325569132258079e-01 +2.4287375974449826e-01 +-2.6862982985407600e+00 +5.6643764655290252e-01 +2.4742391183169232e-01 +-2.7118330330587881e+00 +5.6643764655290252e-01 +2.4742391183169232e-01 +-2.7118330330587881e+00 +-9.7534422549989241e-01 +2.9316029867918258e-01 +-2.4409790792615214e+00 +-9.6129844940581732e-01 +2.6906582507356053e-01 +-1.9276798234191497e+00 +-1.1514443877973211e+00 +2.9853046138206663e-01 +-2.3881595098771751e+00 +5.6892465909424583e-01 +2.9128308870693748e-01 +-2.7160646694576189e+00 +4.7909346102278089e-01 +2.9382289684516544e-01 +-2.6483056745078986e+00 +1.2888975726305232e+00 +3.6659388644913621e-01 +-3.6943347152432837e+00 +-8.3806827242278614e-01 +4.1656376422054991e-01 +-2.5458611140293521e+00 +-3.5959183967579444e-01 +5.0850445022118318e-01 +-3.9201188974378782e+00 +-8.8760631928777145e-01 +4.2482833465984177e-01 +-2.4923929441191639e+00 +-2.8404234549956175e-01 +5.0597753197160900e-01 +-3.7519108689293854e+00 +-1.0167409158388101e+00 +4.3345149555612600e-01 +-2.4259625057978198e+00 +3.5513470119202201e-01 +4.0724388705985881e-01 +-2.6346532146737789e+00 +-8.8127054741252342e-01 +5.2299853807718644e-01 +-3.0781580837194040e+00 +-3.1822891762065869e-01 +5.6036207419323958e-01 +-3.8360769160612116e+00 +-1.4990455118870979e-01 +5.3993579507142286e-01 +-3.5768343016733462e+00 +3.5059416863915915e-01 +4.5603491199632057e-01 +-2.6728329193350824e+00 +3.8567656409030332e-01 +4.6723382328655805e-01 +-2.6372315328179825e+00 +-2.1986869283339500e-01 +6.5153920291380052e-01 +-3.7715889750491760e+00 +-8.9378231700378585e-01 +6.1441747057803003e-02 +-2.4720142508525655e+00 +-9.4831214182351020e-01 +6.1243436860965263e-02 +-2.4442342553668945e+00 +-1.0706913549071482e+00 +7.1644714078020033e-02 +-2.3913126444975221e+00 +-1.2498190856129940e+00 +1.1017918138976954e-01 +-2.3652058311764947e+00 +-1.0078097757914410e+00 +1.1546690319704712e-01 +-2.4162747826253717e+00 +-1.0078097757914410e+00 +1.1546690319704712e-01 +-2.4162747826253717e+00 +6.8623614079471673e-01 +9.1244948568363307e-02 +-2.8016079199493955e+00 +4.4345244633764885e-01 +1.0505362774109483e-01 +-2.6366322773827173e+00 +6.1707856985483100e-01 +1.1258326790494495e-01 +-2.7727973750521353e+00 +6.7619722428516083e-01 +1.1324761860061919e-01 +-2.8191542241357594e+00 +-8.0294617283712155e-01 +1.7991041423131007e-01 +-2.5774218037208456e+00 +-8.8330562955953329e-01 +1.9212897834172837e-01 +-3.0815674246250824e+00 +-7.5312818258426384e-01 +1.8408059060976173e-01 +-2.6573031208774633e+00 +-8.0962499253500508e-01 +1.8984200802411005e-01 +-2.5625117250215999e+00 +6.1751280690702715e-01 +1.6212813585886418e-01 +-2.7751508841790407e+00 +-8.2796396867807176e-01 +1.9749124626568854e-01 +-2.5606485197480997e+00 +9.6562201926710600e-01 +1.7162348346916700e-01 +-3.1611736723409871e+00 +6.9938712868393782e-01 +1.8332024706440966e-01 +-2.8624334319502660e+00 +6.2039371032630675e-01 +1.8497307125434925e-01 +-2.7894138562555306e+00 +7.5150330125950204e-01 +1.8862612782236246e-01 +-2.8960689171749148e+00 +6.5538315591535701e-01 +1.9755281637366170e-01 +-2.7986481665975416e+00 +-7.3900366715181420e-01 +2.3671493908706412e-01 +-2.6929385174560263e+00 +-8.9083172785776366e-01 +2.5382199038824271e-01 +-2.4869622823576392e+00 +-8.7924326520727369e-01 +2.8993097707039689e-01 +-2.5028368509759997e+00 +-9.9038805589900958e-01 +2.9376490230284369e-01 +-2.4252875010615669e+00 +6.8175489086210883e-01 +2.7706114900298834e-01 +-2.8498296421509655e+00 +-9.3471893595173960e-01 +3.0829723294268246e-01 +-2.4664711648925421e+00 +4.3966706232427671e-01 +2.8634237091079262e-01 +-2.6217312035729137e+00 +4.4503122610636831e-01 +2.8945577304539588e-01 +-2.6247457267085590e+00 +-1.0679196659318186e+00 +3.2720439921425826e-01 +-2.4041864814627028e+00 +-2.6079957075641214e-01 +4.3248419641117691e-01 +-3.6967081550747998e+00 +-7.6644639353690980e-01 +4.3307137832701442e-01 +-2.7876474647609126e+00 +-3.2006146154013704e-01 +4.8999987304836323e-01 +-3.8280483837487012e+00 +-8.9786707743645711e-01 +4.1968980485870966e-01 +-2.4931785713877814e+00 +-3.4600086584141682e-01 +5.3117890872177187e-01 +-3.8938565522443822e+00 +-7.3490675688380269e-01 +4.6016911488278095e-01 +-2.6976718234721426e+00 +-7.4331823731959867e-01 +4.7853373531581139e-01 +-2.6773620152561479e+00 +-1.6440974926609636e-01 +5.5821370232967860e-01 +-3.6465620500106097e+00 +-1.7588516864428100e-01 +5.9607747593730998e-01 +-3.7300351682238837e+00 +-1.7659954811014619e-01 +6.0149656986709776e-01 +-3.7324078857995158e+00 +-7.3338279570811726e-01 +5.5273601076993983e-01 +-2.6983489853769513e+00 +-8.4013919878138568e-02 +6.4253024211269594e-01 +-3.7655910309595551e+00 +-5.6432863647982064e-02 +6.4569102711918036e-01 +-3.7583638248082072e+00 +-7.3313429979101130e-01 +5.6153900219543529e-01 +-2.7009121495579334e+00 +-7.4488833306406510e-01 +6.4554481691444598e-01 +-2.6960639499910646e+00 +2.3586490399126786e-01 +5.5759960214574456e-01 +-3.0824327339955158e+00 +-7.7663938382956066e-01 +5.8929520586582351e-01 +-2.6094780321919635e+00 +5.2247864665497057e-01 +2.4153434692870165e-01 +-2.6856629880856526e+00 +3.4501984565900640e-01 +4.1635150549281247e-01 +-2.6560711522164620e+00 +5.5657937409719116e-01 +4.2122736536707839e-01 +-2.7253834650826785e+00 +1.1855352510066557e+00 +5.7490344529086516e-02 +-3.4323597324725892e+00 +6.9640704779209261e-01 +3.6712055948490119e-01 +-2.9449314722351536e+00 +5.8949525698336103e-01 +3.9372558166119226e-01 +-2.7612945325434524e+00 +7.1625603758145262e-01 +4.2009885612153602e-01 +-3.0460217911124889e+00 +-1.0530438054104010e+00 +8.4985161777069260e-02 +-2.3931625949037092e+00 +9.8296769524421768e-01 +1.9803513351521071e-01 +-3.1719294357880226e+00 +1.0983568847257539e+00 +2.0635744423340793e-01 +-3.3109717760476602e+00 +4.1518382231383388e-01 +3.4236059205858227e-01 +-2.6566421459476532e+00 +1.7221077731638362e-01 +5.2321748045865091e-01 +-2.9987211725060625e+00 +5.4886951326582156e-01 +4.7969487532733374e-01 +-2.8067594638028304e+00 +1.1862708750801398e+00 +4.9135748003421673e-02 +-3.4136796507607525e+00 +1.2086707535038272e+00 +5.6731227725928937e-02 +-3.4619432375920955e+00 +9.0743849641606034e-01 +9.6637225930273754e-02 +-3.0634205005480908e+00 +3.7369911841624975e-01 +4.2741261243506168e-01 +-2.6454920617271629e+00 +9.7192770547902496e-01 +3.8391247102564918e-02 +-3.1514031545525092e+00 +9.3821388941492767e-01 +4.8307412700359674e-02 +-3.1145234440134208e+00 +8.8997485396358167e-01 +7.9077689037046539e-02 +-3.0607650768063066e+00 +1.0033588867536001e+00 +2.0714774391641713e-01 +-3.2013357943503600e+00 +4.2205743227527365e-01 +3.9892260719459938e-01 +-2.6662359030089506e+00 +7.9462147464862087e-01 +4.1224363093448091e-01 +-3.2401833273215099e+00 +4.7941439869152835e-01 +4.1085656124554315e-01 +-2.6821758318689168e+00 +1.1713065426017568e+00 +3.7607219153737242e-02 +-3.3967298123219898e+00 +1.1395906442708179e+00 +9.9498588400490320e-02 +-3.3599425344878413e+00 +1.0437638199231678e+00 +1.4630189276468977e-01 +-3.2311807364800971e+00 +1.0437638199231678e+00 +1.4630189276468977e-01 +-3.2311807364800971e+00 +1.0566862304966846e+00 +1.5306033027601648e-01 +-3.2531385617936381e+00 +1.0661384450319507e+00 +2.2434966882038829e-01 +-3.2985897379878830e+00 +1.0845900061496179e+00 +2.4529027176936316e-01 +-3.2805211661815972e+00 +5.4612671419487746e-01 +2.8667655427545552e-01 +-2.6859444302487820e+00 +1.0659445700886288e+00 +2.6483207356716570e-01 +-3.2613729594816832e+00 +1.0687677007003340e+00 +2.7631073311519805e-01 +-3.2527596259567839e+00 +1.0687677007003340e+00 +2.7631073311519805e-01 +-3.2527596259567839e+00 +9.3873632076284974e-01 +3.2190566638792606e-01 +-3.1103493817795496e+00 +9.5313353864618389e-01 +3.3409402747109601e-01 +-3.1220628610809888e+00 +4.8133795403666957e-01 +3.6133051978845243e-01 +-2.6810124764042254e+00 +5.6702006725333731e-01 +3.6658932128694111e-01 +-2.7187795565718611e+00 +5.1264189132775428e-01 +3.7457822048772266e-01 +-2.6873066249492110e+00 +5.1763072033021706e-01 +3.7730403079774189e-01 +-2.6836648936506049e+00 +5.1224479171160453e-01 +3.8642836771232808e-01 +-2.6855879903440480e+00 +1.0268383883976959e+00 +3.9759321884224941e-01 +-3.3417253602110186e+00 +1.0323763098445444e+00 +4.0113206415738978e-01 +-3.3431474472612548e+00 +5.9020716462119294e-01 +4.4798668508816719e-01 +-2.7557276517614451e+00 +1.9123648308180757e-01 +6.0800746730775135e-01 +-3.0632553966826319e+00 +1.1885112025254987e+00 +5.1889360312434178e-02 +-3.4290933822871250e+00 +1.1340010879468025e+00 +1.0327473081444508e-01 +-3.3563909795106341e+00 +1.2540445418249473e+00 +1.0470863031166290e-01 +-3.5521188840148068e+00 +1.0102566713499495e+00 +1.7566963948580708e-01 +-3.1875157424154703e+00 +1.0894004632712158e+00 +2.5546392292584297e-01 +-3.2813811810548268e+00 +4.5810118234552288e-01 +3.9588889605242999e-01 +-2.6617610747864715e+00 +4.0938575216283396e-01 +3.5508629604328129e-01 +-2.6433816059805939e+00 +1.3662201039845194e+00 +-6.1992707958697761e-03 +-2.3218954412265864e+00 +1.3497172649587266e+00 +1.2237452485734823e-02 +-2.3297750366730989e+00 +6.9070426766336868e-01 +9.6528476614286929e-02 +-2.8291593230982826e+00 +3.5737859160930818e-01 +1.6179314690642171e-01 +-2.6470310128785859e+00 +3.7073320767726754e+00 +5.7280907847098127e-02 +-7.5655797953137771e+00 +1.3446228233316511e+00 +7.1527223228212852e-02 +-2.3254801673797467e+00 +1.3333612798762302e+00 +1.5543853684595521e-01 +-2.3997153582737232e+00 +1.2400926350494883e+00 +1.1861670052729088e-01 +-3.5065694600446555e+00 +1.2604786224007059e+00 +1.5384958115385555e-01 +-3.5295986947337199e+00 +1.3165781333036579e+00 +-1.7400426876080244e-01 +-2.4172976379410240e+00 +3.7696525844325683e+00 +2.6287393328852032e-01 +-7.7792034980134801e+00 +3.7696525844325683e+00 +2.6287393328852032e-01 +-7.7792034980134801e+00 +3.8160107861184449e+00 +4.5142770729854509e-01 +-7.8949655901727089e+00 +1.3601047105431223e+00 +6.7623942942037288e-02 +-2.3123345662979662e+00 +1.3612126997396679e+00 +1.0504570036945435e-01 +-2.3379244808839852e+00 +1.3660991465843684e+00 +1.8943179102468286e-01 +-2.3052991567204817e+00 +1.3780847461481851e+00 +2.5980605432559656e-01 +-2.3026800707242119e+00 +4.9738684105347375e-01 +4.4547126926478064e-01 +-2.6681021818439126e+00 +3.0125314600043582e+00 +-2.0068890741089976e-03 +-6.5112183230505529e+00 +1.3546232758378043e+00 +-1.0002014411189262e-02 +-2.3426579400705374e+00 +3.0228863606055461e+00 +1.0871240096965129e-01 +-6.5532467057032155e+00 +3.8229202587425646e+00 +2.5411430360396786e-01 +-7.7238375641830501e+00 +1.3569057142032392e+00 +5.2780425408049857e-02 +-2.3046141849633148e+00 +1.3515307297225347e+00 +6.7593249420145676e-02 +-2.3288950054940845e+00 +1.3212258367755549e+00 +1.3101580111938102e-01 +-3.6219380341614915e+00 +8.7485878010172724e-01 +1.0967964933430806e-01 +-3.0404268006681914e+00 +1.3727958793178563e+00 +1.8922606518328822e-01 +-2.2947615513434818e+00 +3.0302700005171861e+00 +-6.0623210864622162e-02 +-6.5606181582229244e+00 +3.0302692546518983e+00 +3.1531698740016989e-01 +-6.5782763656039780e+00 +3.0097629378558537e+00 +3.3281654425109808e-01 +-6.5587398012841396e+00 +1.3731036837824691e+00 +6.7836454000595736e-02 +-2.3032687601396509e+00 +1.3527859130860402e+00 +7.0064009521263917e-02 +-2.3228015464183729e+00 +1.3689261109716884e+00 +7.0641730421256141e-02 +-2.3080252390668234e+00 +1.8263025501475822e+00 +2.0537176260738815e-01 +-4.4132221900780833e+00 +1.3286078446060534e+00 +1.2861308689490933e-01 +-2.4169191556258496e+00 +1.0592297609363517e+00 +2.6241489506735349e-01 +-3.2375040022599308e+00 +1.3595110791395666e+00 +1.8887906945895730e-01 +-2.3082745028514582e+00 +4.2114525446098161e-01 +2.4331390180180706e-01 +-2.6616512173270053e+00 +1.6247335479787590e+00 +-1.7864287259616277e-01 +-3.9841723528190474e+00 +1.3402388133047274e+00 +2.3030637302003314e-02 +-3.6409550557120123e+00 +1.4936109148474150e+00 +5.2718307598866282e-02 +-3.8404777703438122e+00 +9.7509609076651871e-01 +1.9466201720967375e-02 +-3.1493711086500427e+00 +1.3732211053651764e+00 +5.7710869654993426e-02 +-2.5859620945247501e+00 +3.0119204570438125e+00 +3.1426417760866937e-01 +-6.5631215907234379e+00 +1.3513488492990540e+00 +7.0150536950844652e-02 +-2.3307127696307992e+00 +9.3923371169124004e-01 +9.3644501835897787e-02 +-3.1435604141176934e+00 +8.8634165910649065e-01 +9.7530344310715389e-02 +-3.0777428908617095e+00 +1.1702005854862334e+00 +2.1554076623946153e-01 +-3.4111966277784247e+00 +1.0845723791353139e+00 +2.6021572474118621e-01 +-3.2630109596447658e+00 +1.0754609672024227e+00 +2.6106941315946613e-01 +-3.2625299655032411e+00 +1.3221828689463624e+00 +2.6927773156202794e-01 +-2.3986795201947189e+00 +9.3241739582502359e-01 +3.6242804198418194e-01 +-3.1087102356407930e+00 +8.4842062334796786e-01 +4.1323809343832879e-01 +-3.1591282194810999e+00 +3.7654999948764184e-01 +2.8846368482288581e-01 +-2.6528863806849463e+00 +3.0218189222450227e+00 +-5.3256266600348739e-02 +-6.5553142584344890e+00 +1.0980636164754316e+00 +9.6150389756029832e-03 +-3.3034737763779574e+00 +3.7607628255141656e+00 +2.3272879083884204e-01 +-7.7947302891079469e+00 +9.8868430092136095e-01 +5.8949849640158043e-02 +-3.2014596663432489e+00 +3.0009129841452151e+00 +4.0052314626873492e-01 +-6.5829580128124903e+00 +1.8161716249246473e+00 +2.2947708695500868e-01 +-4.4342171089243445e+00 +8.6941751011638846e-01 +1.0856037494997443e-01 +-3.0335752482271556e+00 +1.0704245716648280e+00 +1.6892268736452104e-01 +-3.2687516438488688e+00 +1.0651207498410495e+00 +2.3901562396508930e-01 +-3.2578849961012852e+00 +9.9087278197674677e-01 +2.4046379211012331e-01 +-3.1872345128010013e+00 +9.9087278197674677e-01 +2.4046379211012331e-01 +-3.1872345128010013e+00 +9.5985694469934668e-01 +2.8436672654975115e-01 +-3.1442792386604550e+00 +1.3647301077157641e+00 +2.4924815997910280e-01 +-2.3221957689865502e+00 +9.4920381518124153e-01 +3.3788214811295314e-01 +-3.1098070035031151e+00 +1.3240063746282860e+00 +3.0803849199571542e-01 +-2.4499488955076001e+00 +8.4206988710561714e-01 +4.0516732107963699e-01 +-3.1669694677546856e+00 +1.3343791338657085e+00 +2.4098705301188583e-01 +-2.3529321079063168e+00 +1.3711910782470040e+00 +6.9710885726984764e-02 +-2.3184074156651859e+00 +1.3713331658367380e+00 +9.3202247925314771e-02 +-2.3061579916840156e+00 +1.3802063504836601e+00 +2.5381825510426548e-01 +-2.3257541161314212e+00 +1.5117485346320083e+00 +3.7726351548590487e-01 +-2.5340428110969384e+00 +1.3733747590291396e+00 +7.4191859596229329e-02 +-2.3061749899245498e+00 +1.3770176291336804e+00 +2.7453169457297949e-01 +-2.3307581880464903e+00 +-1.2988786784520123e+00 +5.7787248725868323e-01 +-2.3860777940192803e+00 +-1.1161568989444908e+00 +5.7925737110698405e-01 +-2.3872688543403253e+00 +-1.2498541344039291e+00 +6.9998384220966381e-01 +-2.3966744820343648e+00 +-1.2950479173902654e+00 +5.3149483899979233e-01 +-2.3810385798590765e+00 +-1.1132036150114912e+00 +5.3630022648813080e-01 +-2.3886886939545660e+00 +1.0638499414126210e+00 +2.4559494703314483e-01 +-3.2700696014408752e+00 +-1.0035091988112919e+00 +6.2540267107827718e-01 +-2.4203883540420161e+00 +-1.1477674166467802e+00 +6.2874360704955401e-01 +-2.3849837097567521e+00 +-1.1477674166467802e+00 +6.2874360704955401e-01 +-2.3849837097567521e+00 +-1.2009472199154174e+00 +7.9611587756279834e-01 +-2.4255374656507485e+00 +1.8493455274712223e+00 +3.2388630775368238e-01 +-4.5937797562018421e+00 +-1.3722157350874404e+00 +5.6619546220508132e-01 +-2.3978823939953990e+00 +-1.2899728864337556e+00 +6.0344519805511576e-01 +-2.4007509741962783e+00 +-1.1485565987932542e+00 +6.0215846378549787e-01 +-2.3920126775323829e+00 +-1.3320434314748661e+00 +6.2801745348739535e-01 +-2.3965498618860099e+00 +-1.1038516677344565e+00 +6.5687053817305141e-01 +-2.4033164514686631e+00 +-1.3896057274070970e+00 +1.9826171114745156e-01 +-2.4134262423614761e+00 +-1.3896057274070970e+00 +1.9826171114745156e-01 +-2.4134262423614761e+00 +-1.4038923763718492e+00 +2.9079372848913504e-01 +-2.4129938651905949e+00 +-1.0822267959077703e+00 +4.9248788337833527e-01 +-2.3998579266351299e+00 +-1.4136546132585339e+00 +6.5668886477345312e-01 +-2.4110720511314532e+00 +-1.1779084674483573e+00 +6.6774252489833108e-01 +-2.3931294362548998e+00 +-1.3917601181219672e+00 +6.9798908892936717e-01 +-2.4485940906357846e+00 +-1.2375954961206195e+00 +6.8908396050315612e-01 +-2.4042907119570409e+00 +1.5756106453474874e+00 +1.8656704757036469e-01 +-4.0295204989078144e+00 +-1.3285151331613689e+00 +1.8345451577147368e-01 +-2.4054064293603998e+00 +-1.3651293116360430e+00 +1.8435084849570632e-01 +-2.4134916672684450e+00 +-1.2310241481271706e+00 +3.2010039488096692e-01 +-2.3775505054712918e+00 +-1.1474728985698379e+00 +4.0608242923917154e-01 +-2.3826250709221095e+00 +-1.1278548718811121e+00 +4.8834260192163026e-01 +-2.3865602624714199e+00 +-1.3844687060588687e+00 +5.1416698533723837e-01 +-2.4054992874704291e+00 +-1.3406766361487346e+00 +5.1458649162313852e-01 +-2.4013935681852887e+00 +-1.1753422361425245e+00 +6.9499032740868916e-01 +-2.3963394736156496e+00 +-1.2902954877076112e+00 +7.2730522290502053e-01 +-2.4094194219308380e+00 +-1.1152362784327732e+00 +7.3234737033443509e-01 +-2.4198059548321362e+00 +1.7854411562163786e+00 +3.6435950251171922e-01 +-4.5105641782049704e+00 +-1.2806453292017446e+00 +2.0961335667204115e-01 +-2.3849274910120828e+00 +1.3356004048865833e+00 +2.0542704076374774e-01 +-2.4099006165433705e+00 +-1.1195051936856131e+00 +2.8654400043713840e-01 +-2.3836557913019836e+00 +-1.1401119974648424e+00 +3.2519382741793712e-01 +-2.3895315944954794e+00 +4.4040699220446816e-01 +4.1194724697673463e-01 +-2.6519965058704851e+00 +-1.1832470051626724e+00 +4.1731034112874615e-01 +-2.3879788906796620e+00 +-1.2959287658798746e+00 +4.2180336686634479e-01 +-2.3927890532409259e+00 +-1.0235504691960533e-01 +1.3058057535537185e-01 +-7.0179332732864508e-01 +-9.7726594672999478e-01 +6.5988927775292816e-01 +-2.4503068319857406e+00 +-1.0264183994036546e+00 +6.7089284132371874e-01 +-2.4260343181452497e+00 +-1.0489347250730803e+00 +6.7566927757295114e-01 +-2.4371982954534235e+00 +-1.1215623438593394e+00 +6.9787770288881856e-01 +-2.3979514296414068e+00 +-1.2494450174439735e+00 +7.2123150202886011e-01 +-2.3981889197349817e+00 +1.6199150348478648e+00 +1.3376220442824202e-01 +-4.0509597056987277e+00 +1.6565313155056904e+00 +1.4762536969554080e-01 +-4.1011898452763811e+00 +1.3367554225918121e+00 +1.0717766395469747e-01 +-2.4163497416238888e+00 +1.2640732360271796e+00 +2.4893955613217891e-01 +-3.5508032147199953e+00 +-1.3694218812457477e+00 +1.8543679270075694e-01 +-2.3992030736152636e+00 +-1.2764013765211240e+00 +2.1986609128363557e-01 +-2.3879627583420486e+00 +-1.2901100790165749e+00 +2.2937972070795390e-01 +-2.4004050764670253e+00 +1.2693405053822457e+00 +3.5181884752161713e-01 +-3.6950445662514957e+00 +-1.2764979364829250e+00 +3.1666681228030880e-01 +-2.3823962270723364e+00 +-1.1471402003238520e+00 +3.9424606894540754e-01 +-2.3851504303545830e+00 +-1.2877182546944854e+00 +4.3138152761149889e-01 +-2.3947918371311014e+00 +-1.2877182546944854e+00 +4.3138152761149889e-01 +-2.3947918371311014e+00 +-1.1624120275473659e+00 +6.4574421734584941e-01 +-2.3868802665957198e+00 +-1.0127677638719819e+00 +6.6269703336074559e-01 +-2.4295251128762438e+00 +-1.0319921354587891e+00 +6.6126927975859895e-01 +-2.4189186868926735e+00 +-1.1062723951748921e+00 +6.6931644422142034e-01 +-2.3758720999751914e+00 +-1.3768149794812623e+00 +7.2166786595831811e-01 +-2.4433961750162658e+00 +-1.0580409597689302e+00 +7.2105063686333493e-01 +-2.4524602227558505e+00 +-1.1034311914383919e+00 +7.1544725071179116e-01 +-2.4147947062171169e+00 +-1.2615663883395893e+00 +8.9197266414823917e-01 +-2.4559762793679849e+00 +1.8677186480233536e+00 +2.2023802639390141e-01 +-4.4835165321586894e+00 +1.8413902442443246e+00 +2.5345587256883906e-01 +-4.4680593910035000e+00 +1.3045137527081561e+00 +2.0450044331419082e-01 +-3.5999299967535690e+00 +1.3787659270215233e+00 +1.4960755714714563e-01 +-2.2938216377408041e+00 +1.2428052559176039e+00 +2.5100152729305814e-01 +-3.5262991826224468e+00 +1.7720729740976913e+00 +3.9147802545671623e-01 +-4.5529794799131853e+00 +1.3308868929561997e+00 +2.1584636453472650e-01 +-2.4049007381082066e+00 +1.3342181222879121e+00 +2.1561963770244441e-01 +-2.4105577160727911e+00 +1.8512392559444331e+00 +4.3923160961570423e-01 +-4.6060659266558819e+00 +1.8263825223207586e+00 +4.4150629230533700e-01 +-4.6385385433041728e+00 +-1.1259451146131259e+00 +3.3432153016145044e-01 +-2.3821348272464946e+00 +-1.1502356482669114e+00 +4.1102282347948038e-01 +-2.3849660125931922e+00 +-1.1842761576087981e+00 +4.8386250296495642e-01 +-2.3982813841359150e+00 +-1.3193634462083927e+00 +5.1405329861750537e-01 +-2.3952789959305409e+00 +-1.1406008318665684e+00 +5.7960807162932071e-01 +-2.3835291584143832e+00 +-1.1564003706719375e+00 +5.8149070487612142e-01 +-2.3933436655350482e+00 +-1.1202736846010612e+00 +6.1133716550787531e-01 +-2.3910317244991766e+00 +-1.0372683456416094e+00 +6.1869220344845532e-01 +-2.4149115743769305e+00 +-1.0611512309394544e+00 +6.1905173388527679e-01 +-2.4064665051003820e+00 +-1.0852938561095298e+00 +6.2031926497132817e-01 +-2.4000431415366057e+00 +-1.2574829601844950e+00 +6.4613256828423260e-01 +-2.3950393362733458e+00 +-1.3065873051661896e+00 +6.7369402133315859e-01 +-2.3981286476759047e+00 +-1.3695427062257493e+00 +7.1446690491833342e-01 +-2.4447679449335920e+00 +-1.2260011686287657e+00 +7.4288781362037759e-01 +-2.4029154334744502e+00 +-1.0820558880184239e+00 +8.2385727893451677e-01 +-2.5694428378292495e+00 +-1.1316822972165734e+00 +8.8341197248909209e-01 +-2.6366729542664626e+00 +1.2636060937258835e+00 +1.5418538709889842e-01 +-3.5401021779907254e+00 +1.8562293546454980e+00 +2.2450571245179843e-01 +-4.5118219366493042e+00 +1.8459778836030123e+00 +2.3975018815705285e-01 +-4.4792315664510785e+00 +1.8450741119986589e+00 +2.6143379996542598e-01 +-4.5079495460887253e+00 +-1.1263514169658568e+00 +1.2844032657708576e-01 +-2.0600731281026872e+00 +-1.3454826660916690e+00 +1.5716965402446731e-01 +-2.4070218775672418e+00 +1.7769717992210323e+00 +3.6691337031756871e-01 +-4.5331964832219898e+00 +-1.1300898968175588e+00 +2.4427360283736546e-01 +-2.3817990845977404e+00 +-1.1221385813479590e+00 +2.4919401493785587e-01 +-2.3847217899486877e+00 +-1.4274139460980848e+00 +2.6440123236415475e-01 +-2.4057954838357003e+00 +-1.2797594819042395e+00 +2.6418766843433628e-01 +-2.3941597357565940e+00 +1.3812670509945015e+00 +2.6887028445366024e-01 +-2.3163986157547289e+00 +4.5079907051303636e-01 +4.3391853769044542e-01 +-2.6618485929922553e+00 +4.6722738980234801e-01 +4.5098363388875323e-01 +-2.6872680687050381e+00 +-1.3089172982429984e+00 +4.2726550457246104e-01 +-2.3925135567495142e+00 +-1.3088388875374213e+00 +4.2735154832430006e-01 +-2.3928207734828932e+00 +-1.3220534751880770e+00 +4.2740482214251219e-01 +-2.3937933795171622e+00 +-1.3238290042829410e+00 +4.2782478371303562e-01 +-2.3972455856032289e+00 +-1.1229102065399443e+00 +4.2608076165721914e-01 +-2.3817844848487142e+00 +-1.1229102065399443e+00 +4.2608076165721914e-01 +-2.3817844848487142e+00 +-1.1215777536412188e+00 +4.3521263726475495e-01 +-2.3804152853095175e+00 +-1.1215777536412188e+00 +4.3521263726475495e-01 +-2.3804152853095175e+00 +-8.7943207878213123e-02 +1.1106958729257613e-01 +-6.9116159099311825e-01 +-1.1231169055075931e+00 +4.6279440291781976e-01 +-2.3850867020689939e+00 +-1.1219109568844166e+00 +5.1059320828164867e-01 +-2.3862581481804446e+00 +-1.4244805973311874e+00 +6.1552112081795296e-01 +-2.4036837769179096e+00 +-1.2142398818359621e+00 +6.0915064351498927e-01 +-2.3840508493750336e+00 +-1.3436394560474663e+00 +6.2201908739766532e-01 +-2.4051901556547777e+00 +-9.2407300538079029e-01 +6.3128807372813378e-01 +-2.4598190156352429e+00 +-1.1165509227167207e+00 +6.2045391389721505e-01 +-2.3859201635529801e+00 +-1.2638265387507817e+00 +6.6967269212505665e-01 +-2.4000127878074480e+00 +-1.1147899414644156e+00 +6.6753140726395344e-01 +-2.3941297606390113e+00 +-1.2298811768572389e+00 +7.1492482636187149e-01 +-2.4016146669442282e+00 +-1.2660269813293845e+00 +7.4233708617274186e-01 +-2.4035876012224073e+00 +-1.2157368276472489e+00 +7.4743209297967494e-01 +-2.3962909647498365e+00 +-1.1476261080334700e+00 +7.4303291830220408e-01 +-2.3814014992392196e+00 +1.2597146008736770e+00 +1.7419182471738334e-01 +-3.5427332270134042e+00 +1.8580103637522285e+00 +2.8745081820275831e-01 +-4.5322532366680903e+00 +1.3223059182265269e+00 +1.7649701040759827e-01 +-2.4332907974526075e+00 +-1.1144961262138553e+00 +2.0384722654386139e-01 +-2.3826163563263378e+00 +-1.2848483387368135e+00 +2.0800921875240599e-01 +-2.3986649949983350e+00 +1.8496964945105123e+00 +4.1670651091337158e-01 +-4.6267487406713697e+00 +-1.1070338557086414e+00 +3.1261658599686787e-01 +-2.3891744905071719e+00 +-1.1547493811858540e+00 +3.2495214407801176e-01 +-2.3913434189336296e+00 +-1.3087712998945327e+00 +4.4620942184619677e-01 +-2.3945265256265023e+00 +-1.3087712998945327e+00 +4.4620942184619677e-01 +-2.3945265256265023e+00 +-1.3962535857770533e+00 +4.9861170575257752e-01 +-2.4010438685433853e+00 +-9.8316284551584332e-01 +5.1181099432568122e-01 +-2.4296298940514527e+00 +-1.1846645389304229e+00 +5.1012260170038615e-01 +-2.3888607856774988e+00 +-1.3221580261095724e+00 +5.1458820520451143e-01 +-2.3871988731020406e+00 +-1.1000088332268394e+00 +5.3122155515533764e-01 +-2.3535581844996591e+00 +-1.2590707599921664e+00 +5.9870853861366213e-01 +-2.3980119090297829e+00 +-1.1641981613956391e+00 +5.9819734995722773e-01 +-2.3919368129722458e+00 +-9.8708648492146311e-01 +6.3313980263710978e-01 +-2.4225636767885312e+00 +-1.2248607822242368e+00 +6.5161013774140231e-01 +-2.3895743603164781e+00 +-1.3686901785107404e+00 +7.2283913801640975e-01 +-2.4438124897526237e+00 +-1.2214451147994494e+00 +7.3174060640723382e-01 +-2.3978018138489108e+00 +-1.2153328233919607e+00 +7.3311963637600097e-01 +-2.3989473006464070e+00 +-1.2399217994060441e+00 +7.3069586823863142e-01 +-2.3839196581932285e+00 +-1.2671538547072863e+00 +8.8937816421088522e-01 +-2.4550175614210850e+00 +-1.2635633474013790e+00 +9.2052465022617402e-01 +-2.4560821319022597e+00 +1.3259091616639487e+00 +1.3128441150462580e-01 +-3.6370174645597899e+00 +1.2687246700619816e+00 +1.6842892513121580e-01 +-3.5519523561982771e+00 +3.0131480234923664e+00 +4.2541478480228290e-01 +-6.8927069647248356e+00 +1.8358938767671520e+00 +2.8947328803510392e-01 +-4.5031791616806673e+00 +1.3442299410818430e+00 +1.5820735675416728e-01 +-2.3609098169783622e+00 +1.7802692733653127e+00 +3.5811027773477266e-01 +-4.5217698406652174e+00 +3.1242535946398093e+00 +5.8456498309225147e-01 +-6.9744313423901154e+00 +1.8656913067857808e+00 +4.4155420219241004e-01 +-4.6252204558038628e+00 +1.8243049479427291e+00 +4.4194530587611963e-01 +-4.6155919847971969e+00 +-1.1550327973076551e+00 +3.2409763706794364e-01 +-2.3841765900904885e+00 +-1.3156345393324309e+00 +5.5609489147863589e-01 +-2.3921087630537401e+00 +-1.1414179063944521e+00 +5.5525692738049115e-01 +-2.3823077936755150e+00 +-1.0640477736004095e+00 +6.7245151113202617e-01 +-2.5312994164668630e+00 +-1.0376500791292820e+00 +6.4724389289468942e-01 +-2.4214101726932631e+00 +-1.0397011830229148e+00 +6.4597924544059437e-01 +-2.4134507930376077e+00 +-1.1724501165896215e+00 +6.5178853021261418e-01 +-2.3871385421948941e+00 +-1.1867349394269211e+00 +6.5951318247907598e-01 +-2.3931936505919267e+00 +-1.1585382461335236e+00 +6.7828421085440394e-01 +-2.3926087861303831e+00 +-1.1152732337340177e+00 +6.7815003503541782e-01 +-2.3877485927577009e+00 +-1.2636449728281418e+00 +7.2940993441828961e-01 +-2.4046169692692669e+00 +-1.2294669091968422e+00 +7.2993123272802063e-01 +-2.3846061029826591e+00 +1.5466792435326093e+00 +3.1204084630479434e-01 +-5.2043414036833173e+00 +1.8453778908506511e+00 +4.3129203658308196e-01 +-4.5998356375512426e+00 +1.0367308388421252e+00 +3.8162687011538116e-01 +-3.3305964430298518e+00 +1.8366582459891789e+00 +5.4275483463163954e-01 +-4.6198789396096220e+00 +1.8454147405985908e+00 +5.5382808409004236e-01 +-4.6569047040898282e+00 +1.8394670861956599e+00 +5.6681412512457419e-01 +-4.6396285685191954e+00 +-1.1360229619023061e+00 +3.8937897591135534e-01 +-2.3833716275730081e+00 +4.8482257012122620e-01 +4.4618272380524310e-01 +-2.6732613694810174e+00 +-1.1261241336101320e+00 +5.6353795472793955e-01 +-2.3861426570727753e+00 +-1.1266507353937940e+00 +5.8156630823751032e-01 +-2.3882625235036463e+00 +-9.8971415371710947e-01 +6.0972709598114083e-01 +-2.4316173931183909e+00 +4.6763439576732008e-01 +4.4477692282769787e-01 +-2.6960662686537922e+00 +1.4443259655747305e+00 +8.0480038302932697e-02 +-2.2513546604741212e+00 +1.4444258763702704e+00 +-4.2153403581556288e-02 +-2.2382760170653144e+00 +1.9469954165911119e+00 +1.4798428862098142e-01 +-3.4807614333216632e+00 +5.1848078613776860e-01 +-6.0508592012635497e-02 +-2.6734588696205481e+00 +5.1849069311664420e-01 +-6.0616166357594307e-02 +-2.6735780305111119e+00 +9.3927078750557080e-01 +1.5699446601045292e-02 +-3.1272532253779870e+00 +6.1205606823582970e-01 +4.1307426657436773e-02 +-2.7730071007593260e+00 +1.0804821717541835e+00 +1.3886708535518930e-01 +-3.2715584730343648e+00 +1.3924348309384693e+00 +1.4497678523996568e-01 +-2.3095292857017795e+00 +1.5737964618564619e+00 +8.4141036388270835e-02 +-3.9605545182403046e+00 +1.9720288081153372e+00 +1.1040706649273661e-01 +-3.5446149316290647e+00 +1.3255730643779495e+00 +5.8678011032833419e-02 +-2.4045938784082108e+00 +1.3407704980519017e+00 +9.2380054177342533e-02 +-2.3474287187758072e+00 +1.4580586339022605e+00 +2.0621706503525811e-01 +-2.2384385866390279e+00 +3.2074621561989153e-01 +4.1000041692788575e-01 +-2.6586626194071936e+00 +4.1113214534237408e-01 +4.2528356432037301e-01 +-2.6539558266045118e+00 +3.0769920148348928e-01 +-9.1722391701949110e-02 +-2.6591293180227047e+00 +1.0247911278175910e+00 +4.2397056849630514e-02 +-3.2137164787905057e+00 +1.8766978413951956e+00 +7.2156757238951402e-02 +-3.4254720346702499e+00 +1.4109621121761085e+00 +5.2534685891041842e-02 +-2.2845044582230618e+00 +3.0280081623370486e-01 +2.7307417208761103e-01 +-2.6658716345676154e+00 +3.0280081623370486e-01 +2.7307417208761103e-01 +-2.6658716345676154e+00 +3.3146702664844707e-01 +3.5674239031452881e-01 +-2.6567638359929560e+00 +4.7342152306239083e-01 +-9.3966787933511695e-02 +-2.6651374783040334e+00 +6.2654623998438119e-01 +-7.4292837467515263e-02 +-2.7780166406464581e+00 +1.4486228111112671e+00 +-7.0512704397618253e-02 +-2.2362965989930044e+00 +1.4486228111112671e+00 +-7.0512704397618253e-02 +-2.2362965989930044e+00 +1.3344846300728730e+00 +-4.7718743358006230e-02 +-2.3421173375933635e+00 +1.3344846300728730e+00 +-4.7718743358006230e-02 +-2.3421173375933635e+00 +1.4543493602738888e+00 +-2.0232387422765563e-02 +-2.2438734948683141e+00 +1.5570518140590033e+00 +7.0174962297427604e-02 +-3.9295031940319833e+00 +9.8085921771840088e+00 +8.0969181675501545e-01 +-1.5626880027286489e+01 +1.4560905125011634e+00 +1.0091303645766876e-01 +-2.2390375088106214e+00 +1.3345159317376054e+00 +1.8931164252859797e-01 +-2.3447552308499664e+00 +1.4612793078996971e+00 +2.6359487760336819e-01 +-2.2448716954145480e+00 +4.3781557975125035e-01 +-9.9955487779368954e-02 +-2.6507909666410892e+00 +5.7822611577990479e-01 +-6.1815275190476374e-02 +-1.8896645676117034e+00 +5.1436268840915578e-01 +-7.5482574202754879e-02 +-2.6787579103073211e+00 +1.4467146083669240e+00 +-3.7464243449552258e-02 +-2.2407908871958901e+00 +1.3292426465761220e+00 +-2.6243535533465603e-02 +-2.3582211697757249e+00 +1.4543426640509700e+00 +6.7956533176863246e-02 +-2.2440012017088931e+00 +3.0207232115853655e-01 +8.1367572939172420e-02 +-2.6611332445962881e+00 +1.4609006940305023e+00 +1.6692212135985396e-01 +-2.2513163777890988e+00 +1.4555695440198295e+00 +1.7957432395198097e-01 +-2.2470767992476217e+00 +1.4555695440198295e+00 +1.7957432395198097e-01 +-2.2470767992476217e+00 +7.9105048333351469e-01 +2.4528738790682347e-01 +-2.9360511269161784e+00 +1.3956616907559141e+00 +3.0267352960340888e-01 +-2.2959755874924270e+00 +4.3468765851225294e-01 +-8.5831797331100287e-02 +-2.6548772436038819e+00 +1.4244095735516582e+00 +-4.1249970834350752e-02 +-2.2509356307099941e+00 +1.4587742222783378e+00 +-3.7094488593564033e-02 +-2.2272868974536655e+00 +4.0867933631056258e-01 +-2.3543792496011112e-02 +-2.6482529521497837e+00 +1.8962280967286833e+00 +1.5564760181139999e-02 +-3.4483852620350941e+00 +1.8800732885897009e+00 +4.3555068997614889e-02 +-3.4216529001903386e+00 +1.4114884272267558e+00 +5.8002741112837729e-02 +-2.2852671102060751e+00 +1.8535249155816356e+00 +2.9145895573116831e-01 +-4.4074286715785798e+00 +1.4550978577566389e+00 +1.5980945633851557e-01 +-2.2538579778047652e+00 +1.4435114447766275e+00 +1.9012756326690647e-01 +-2.2390115065059195e+00 +1.4711424016621319e+00 +2.7447124800311767e-01 +-2.2336582878170996e+00 +4.1175178190384726e-01 +2.5550828504552520e-01 +-2.6476665475239027e+00 +4.3076345138890082e-01 +3.2964478561514954e-01 +-2.6574420774710150e+00 +3.2707510222559000e-01 +4.0831639733118419e-01 +-2.6566681066980942e+00 +4.8419519417569123e-01 +4.4582445313590940e-01 +-2.6719912209377936e+00 +5.1696049281203849e-01 +-9.5617531023867136e-02 +-2.6913686746398606e+00 +1.8333459631303028e+00 +-1.3331337890211681e-01 +-3.3934055662371825e+00 +4.7968038325440687e-01 +-8.7132568463162155e-02 +-2.6695805017627596e+00 +1.8163216944895169e+00 +-1.2387570937153410e-01 +-3.4038457233435180e+00 +1.8325243109552898e+00 +-9.1855224339393596e-02 +-3.4046523262513286e+00 +1.6401425298800789e+00 +-7.0849502341720424e-02 +-4.0208036756143404e+00 +1.8286340567332722e+00 +7.1806449411190063e-02 +-3.3340343939379076e+00 +1.8493664342321459e+00 +8.1579279787809864e-02 +-3.3612346564885089e+00 +1.6656296023014967e+00 +1.4541890367206289e-01 +-4.0923735468417171e+00 +1.3402524038541963e+00 +6.6516939062428296e-02 +-2.3532692922509826e+00 +1.4577309480560448e+00 +6.9027743154898985e-02 +-2.2374387770601207e+00 +1.4161492311991606e+00 +8.5030312551001824e-02 +-2.2720864373136851e+00 +1.7964816233533587e+00 +3.9012749048049017e-01 +-4.4338250035886455e+00 +1.4306410207322613e+00 +1.8989241029745382e-01 +-2.2610692841974918e+00 +1.4598060613777168e+00 +1.9107219860957947e-01 +-2.2367769174435512e+00 +1.4662670267215612e+00 +1.9029799041400994e-01 +-2.2248647760509201e+00 +1.4624696043760304e+00 +1.9029076195340477e-01 +-2.2265124946945414e+00 +1.4131129321966200e+00 +2.5194932270000980e-01 +-2.2875545258785870e+00 +1.4583348583950388e+00 +2.5825173771129190e-01 +-2.2416877515259626e+00 +2.0537654250062021e+00 +4.9959903594692401e-01 +-2.9213092824018001e+00 +2.0480796679212476e+00 +5.0016868409093207e-01 +-2.9276499766677486e+00 +2.0559213607099478e+00 +5.0322117321151516e-01 +-2.9163705052907014e+00 +2.0105918227875481e+00 +5.2329162794196216e-01 +-2.9866794898916518e+00 +1.2191996217109582e+00 +2.6328449607505400e-01 +-1.9846456979491303e+00 +5.3786980588039623e-01 +3.3707046849009931e-01 +-2.7037249579813514e+00 +3.8879663391347380e-01 +3.7577125996012395e-01 +-2.6460037112405561e+00 +3.4852191451104259e-01 +4.0863773337715154e-01 +-2.6582903601039107e+00 +1.8330375692924181e+00 +-9.7503633040239665e-02 +-3.3973225242251828e+00 +1.4723362433084073e+00 +-7.3218688716539096e-02 +-2.2152240940512704e+00 +1.4097160249942009e+00 +-6.1621153770116212e-02 +-2.2726300841291298e+00 +1.8508846075446279e+00 +2.0630336946313438e-01 +-4.4453779700671028e+00 +1.4227934558836093e+00 +8.7416986690014881e-02 +-2.2756594666795813e+00 +3.9981916545700391e-01 +8.3041976673487436e-02 +-2.6601009709427905e+00 +1.8605697529624674e+00 +2.7911204929850930e-01 +-4.3944926148050429e+00 +1.8357531028401541e+00 +4.2870567401892834e-01 +-4.5538905624191459e+00 +5.6681568568007412e-01 +4.2640840154035986e-01 +-2.7351690131537696e+00 +4.7730036586028268e-01 +4.2744105858158571e-01 +-2.6761982988910389e+00 +4.7715994802961442e-01 +4.2728527894731227e-01 +-2.6757895457625138e+00 +4.0505968337097231e-01 +4.6326159458662142e-01 +-2.6504420947287013e+00 +1.8079136999979160e+00 +6.3497083081891309e-02 +-3.2697310225995495e+00 +1.4404817056624546e+00 +9.4857097958912090e-02 +-2.2540727452328624e+00 +1.8285219749437964e+00 +2.7060973240257480e-01 +-4.4630539339372888e+00 +1.8453337657149491e+00 +3.3603756587819933e-01 +-4.4376556369710949e+00 +1.8291686897786681e+00 +4.3886541510853833e-01 +-4.5387904501347327e+00 +1.5082318274782631e+00 +3.5747919012574891e-01 +-2.5202431034422852e+00 +7.7416912916939911e+00 +1.7891358674523689e-01 +-1.3416131586308481e+01 +7.7416912916939911e+00 +1.7891358674523689e-01 +-1.3416131586308481e+01 +5.3812358357008181e+00 +7.5231757797328003e-01 +-1.0686640796885548e+01 +1.8379851893040164e+00 +3.4723315079021377e-01 +-4.4370553055217687e+00 +1.7902221712639870e+00 +3.9242375768163135e-01 +-4.4514625268665879e+00 +1.8056592223290830e+00 +5.0619874911558171e-01 +-4.5576825837655930e+00 +1.5232859415209199e+00 +3.6832514702173402e-01 +-2.5183072395916861e+00 +9.8593470428816357e+00 +1.1418830574199637e+00 +-1.5538138396871913e+01 +4.2357850683258452e-01 +1.1651005229905793e-01 +-2.7173894695516689e+00 +3.1716018520577172e-01 +3.2415101278264385e-01 +-2.6521180404811431e+00 +4.0620125207751090e-01 +3.2346245121952544e-01 +-2.6869125461768921e+00 +4.0504488888638740e-01 +3.2331252142429151e-01 +-2.6849185343167639e+00 +3.2254996839067390e-01 +2.7559599565223213e-02 +-2.6304093867342875e+00 +3.4226288247104153e-01 +2.0250480103188626e-01 +-2.6733372475002746e+00 +8.0818685245079258e-01 +3.0429462164338905e-01 +-3.0113142949714837e+00 +1.0254788167923141e+00 +3.8255572100359003e-01 +-3.3481955540443069e+00 +3.6242408084377009e-01 +4.2634026571306066e-01 +-2.6413307567724744e+00 +4.8636749601288820e-01 +3.8754649613106817e-02 +-2.6583211223060270e+00 +5.7517215617077089e-01 +9.6300490546996811e-02 +-2.7233840981478417e+00 +9.8345811834188290e-01 +1.5154460919019611e-01 +-3.1604894612883574e+00 +1.7303950594626176e+00 +1.7450957208769083e-01 +-3.1699838882044262e+00 +5.2645973076767238e-01 +1.6873483912933543e-01 +-2.6863524140836481e+00 +2.4933857238440676e-01 +2.8316991783953060e-01 +-2.6353271856060161e+00 +1.9173739516593002e+00 +4.4742460227500597e-01 +-3.0236878844234192e+00 +1.7925124265776873e-01 +4.1365396704160307e-01 +-2.7901968939688926e+00 +-4.6207000074658428e-01 +-2.9618121228416879e-05 +-6.2326958586366166e-01 +-3.8478457751412642e-01 +8.4611947063285460e-03 +-6.5604270712223889e-01 +1.3214301629065328e+00 +7.3049701081450036e-02 +-2.4069801512247122e+00 +1.3193210177570351e+00 +7.2741173597771491e-02 +-2.4033513718981552e+00 +4.3331748957747585e-01 +1.1706543705024741e-01 +-2.7337043088743989e+00 +4.3331748957747585e-01 +1.1706543705024741e-01 +-2.7337043088743989e+00 +3.8689222141762980e-01 +1.9795480502845306e-01 +-2.6475354101453012e+00 +1.7614624860833392e+00 +3.1973497494241787e-01 +-3.1553168612118370e+00 +8.6119141486769157e-01 +3.1808205195135342e-01 +-3.0350815455314542e+00 +3.9627052879965563e-01 +3.0406282585868460e-01 +-2.6697223652814448e+00 +3.4801151792400425e-01 +3.0362864707985154e-01 +-2.6713974154455511e+00 +3.4531869352505695e-01 +3.0309703887750128e-01 +-2.6660439277436252e+00 +2.3856392463553983e-01 +3.0458300223502627e-01 +-2.7472331247691724e+00 +2.3856392463553983e-01 +3.0458300223502627e-01 +-2.7472331247691724e+00 +2.9234513831379610e-01 +3.5028636158145110e-01 +-2.6730416628353977e+00 +3.9992252194770639e-01 +4.0645452136924937e-01 +-2.6688781685594374e+00 +3.9992252194770639e-01 +4.0645452136924937e-01 +-2.6688781685594374e+00 +2.5791313780212288e-01 +4.0708405572998396e-01 +-2.6977929817466424e+00 +1.9987304550565632e+00 +5.1779853974873891e-01 +-3.0534183701432362e+00 +2.0004210554984514e+00 +5.1876319847463404e-01 +-3.0560787532356239e+00 +3.9667152719660631e-01 +4.4603815226590671e-01 +-2.6618938639338730e+00 +4.4805530408757382e-01 +5.6926911965980387e-01 +-3.0860048910190891e+00 +-4.4819174592629191e-01 +1.1986703750085734e-02 +-6.2434739987920995e-01 +3.2428038829510780e-01 +-5.3122690212751546e-02 +-2.5873587918757459e+00 +1.8034901744031870e+00 +1.3677247139893575e-01 +-3.2603209145154892e+00 +9.9567467450012204e-01 +1.6539417937448622e-01 +-3.1778458244803134e+00 +2.1108063653102667e+00 +1.7637749228519992e-01 +-3.7140487469467129e+00 +1.6184760495542780e+00 +1.7261027234444459e-01 +-3.0021554396551089e+00 +5.3984662944105144e-01 +2.4356627349232834e-01 +-2.6971390598940159e+00 +5.2740820750334749e-01 +2.4306956714706709e-01 +-2.6759956328997769e+00 +3.6448554084570706e-01 +3.0826574139641555e-01 +-2.6680328584600264e+00 +2.9324223316738912e-01 +3.0944426966205379e-01 +-2.6987013327505407e+00 +2.9324223316738912e-01 +3.0944426966205379e-01 +-2.6987013327505407e+00 +3.2953726894654783e-01 +3.3489124939659748e-01 +-2.6637024341085938e+00 +2.1603576914786235e-01 +3.4824253615884587e-01 +-2.7342336109335177e+00 +1.8883030059105881e+00 +5.2782606665960718e-01 +-3.0167199137313578e+00 +-3.8858248372334925e-01 +-3.0037570726767142e-03 +-6.4504017830627491e-01 +2.1221238933110370e-01 +-5.5679941024726190e-02 +-2.7000141254559509e+00 +3.0690716091851183e-01 +-5.6786195012294767e-02 +-2.6685789892580956e+00 +3.0690716091851183e-01 +-5.6786195012294767e-02 +-2.6685789892580956e+00 +-4.5289148633366694e-01 +4.6272297966985218e-02 +-6.3694623393814320e-01 +-4.4952819117708065e-01 +5.1623221061762106e-02 +-6.4740111086256891e-01 +3.4244341015850788e-01 +-3.6198471324306244e-02 +-2.6162150894294989e+00 +4.3420717372388196e-01 +4.8935941510520192e-02 +-2.6506790234512181e+00 +5.4537119022057068e-01 +7.8547480062160210e-02 +-2.6967438634327623e+00 +3.3100163581934344e-01 +1.1473063733796215e-01 +-2.6604363686126997e+00 +1.6621313062481022e+00 +1.3917449222080400e-01 +-3.0591316634105583e+00 +1.6621313062481022e+00 +1.3917449222080400e-01 +-3.0591316634105583e+00 +3.9754420995452833e-01 +1.4407637753774491e-01 +-2.6623191859420099e+00 +4.7125445177043840e-01 +1.6754670792738827e-01 +-2.6724533113826956e+00 +3.7038450815153867e-01 +1.9235783618579544e-01 +-2.6690660933452541e+00 +3.6559797622180068e-01 +2.0821869760123141e-01 +-2.6610692626330259e+00 +5.6841905019496641e-01 +2.5783570331651451e-01 +-2.7257626491960223e+00 +7.7674595081164988e-01 +2.8133111823677703e-01 +-2.9354527420968028e+00 +4.1203722429488132e-01 +2.6645065457387690e-01 +-2.6427018497589745e+00 +3.3164528256967074e-01 +3.1564578418062850e-01 +-2.6718354408157965e+00 +4.6842852195138812e-01 +3.5653239194532582e-01 +-2.6741980990964227e+00 +2.0164270289541597e-01 +4.0730752305419621e-01 +-2.7478643013292205e+00 +2.3531952586566171e-01 +4.1195581472996828e-01 +-2.7245437953127398e+00 +5.1925765413308411e-01 +4.2539691110899036e-01 +-2.6973642299975613e+00 +3.2044502510795636e-01 +4.2715898142268871e-01 +-2.6870375121636716e+00 +2.6492680827732895e-01 +4.2757086864214155e-01 +-2.7055244767511089e+00 +3.6240967664988299e-01 +4.3722817070167480e-01 +-2.6647671334805927e+00 +3.5615243656417483e-01 +4.6428556261547799e-01 +-2.6726791588748418e+00 +3.9980747470795497e-01 +-4.7277244924044635e-02 +-2.6327585138625937e+00 +4.1379410743936379e-01 +-4.8411587688026531e-02 +-2.6568771317936037e+00 +3.8135612475616659e-01 +-4.8239138060240348e-02 +-2.6666911672381093e+00 +3.3089060310128376e-01 +-4.4436932044743464e-02 +-2.6123754398103500e+00 +3.3089060310128376e-01 +-4.4436932044743464e-02 +-2.6123754398103500e+00 +3.6292292670515369e-01 +1.1024822550159364e-02 +-2.6327970289959404e+00 +4.0434243672859960e-01 +3.0067382150696254e-02 +-2.6433466326012662e+00 +4.0434243672859960e-01 +3.0067382150696254e-02 +-2.6433466326012662e+00 +4.8867230669843648e-01 +3.7301564508264183e-02 +-2.6691933251668414e+00 +5.1286673090445845e-01 +3.7508957849051006e-02 +-2.6706779037616060e+00 +3.5284078455125073e-01 +4.9487347408887210e-02 +-2.6640691404868009e+00 +2.8288973434308506e-01 +8.8176652466311609e-02 +-2.7019734555747745e+00 +4.0383607421561557e-01 +1.0154817684973158e-01 +-2.6494667203291153e+00 +7.1669571125161902e-01 +1.1822992095819185e-01 +-2.8539151020123272e+00 +7.3799077219983145e-01 +1.3155732337698792e-01 +-2.8843685202549914e+00 +2.0791192746011324e+00 +1.5853274308603971e-01 +-3.6957695562883495e+00 +6.0324008526504314e-01 +1.5305719445057195e-01 +-2.7565960612329183e+00 +3.8789254559731634e-01 +1.8274122290190900e-01 +-2.6521436476312470e+00 +3.9203588529449651e-01 +1.9027066846053989e-01 +-2.6449983118578220e+00 +5.2477380798023343e-01 +2.1904817296515838e-01 +-2.6927868981496039e+00 +1.8471244214908136e+00 +3.0362768532324802e-01 +-3.3194572461933309e+00 +1.8628478601533525e+00 +3.6464777732547560e-01 +-3.3198891887226725e+00 +1.9981132759545975e-01 +2.9866437197153128e-01 +-2.7223505511218922e+00 +5.4160515895702865e-01 +3.1255383132047976e-01 +-2.7035295706373059e+00 +4.2435523595457819e-01 +3.3041340328384217e-01 +-2.6521835316139262e+00 +3.3273960480856241e-01 +3.4407350863224295e-01 +-2.6613390492568691e+00 +5.4023247750291503e-01 +3.7920795999424561e-01 +-2.6909768001984329e+00 +1.9301103425300958e+00 +4.5375095825166789e-01 +-3.0149232598851774e+00 +1.9606034642868946e+00 +4.6024290602924339e-01 +-3.0038982014294837e+00 +1.9335322833783841e+00 +4.6500717510946576e-01 +-3.0068247863651347e+00 +1.9352385911029835e+00 +4.6479472703722419e-01 +-3.0077253117280969e+00 +4.3319805387290988e-01 +3.8556549803617757e-01 +-2.6560694909535791e+00 +5.3243161448452392e-01 +4.0641178671314454e-01 +-2.7003049359607814e+00 +3.6858995543139866e-01 +4.0226396772219863e-01 +-2.6613884021149521e+00 +3.6858995543139866e-01 +4.0226396772219863e-01 +-2.6613884021149521e+00 +3.7596943657256376e-01 +4.0878311113397486e-01 +-2.6572319222458960e+00 +4.1231957496081245e-01 +4.1328976364190612e-01 +-2.6584769550720657e+00 +3.6086603494406050e-01 +4.1921129706214788e-01 +-2.6601849757829812e+00 +3.6194692085202174e-01 +4.1930439745438502e-01 +-2.6621298965540783e+00 +5.7030181245849820e-01 +4.3691336866312241e-01 +-2.7379329363946683e+00 +1.8405259174281313e-01 +4.2423093976723136e-01 +-2.7822884362478773e+00 +4.5154158218124191e-01 +4.3903939972968065e-01 +-2.6831645198303913e+00 +3.7836039895366852e-01 +4.3802178215279852e-01 +-2.6605624123451714e+00 +1.9974689464981946e-01 +4.4206829350776383e-01 +-2.7749153021439446e+00 +6.1333566797774230e-01 +4.7300928399186482e-01 +-2.8224385113930079e+00 +3.9428587335243837e-01 +4.5233801672006185e-01 +-2.6743647002872732e+00 +3.6795759862900551e-01 +4.6377423928626627e-01 +-2.6538364738697990e+00 +-3.7649691239261435e-01 +-8.2224129996022639e-03 +-6.4095281619608480e-01 +-3.8076129311978807e-01 +-7.8811103329993019e-03 +-6.4308676083745386e-01 +-4.3309761007963488e-01 +1.6315489037278280e-02 +-6.3745688686205737e-01 +-4.4770810477542239e-01 +4.7778453138109946e-02 +-6.4645540013857916e-01 +-4.4770810477542239e-01 +4.7778453138109946e-02 +-6.4645540013857916e-01 +4.3903330688677628e-01 +-4.7497316537709638e-02 +-2.6185041949575436e+00 +5.4525175071436782e-01 +-5.2301770566618389e-02 +-2.6975176162005319e+00 +-4.4965200060612820e-01 +5.0177405422847994e-02 +-6.5262047370720166e-01 +5.1317296367606335e-01 +-4.4317905744581547e-02 +-2.6567296501925024e+00 +5.1317296367606335e-01 +-4.4317905744581547e-02 +-2.6567296501925024e+00 +-4.5613785164509663e-01 +5.5095515538054002e-02 +-6.4672588631814476e-01 +4.9728126460992272e-01 +-3.1135889138002033e-02 +-2.6480692891702051e+00 +-4.5334599890015537e-01 +5.8034251070247421e-02 +-6.4943192789714410e-01 +4.5128679385640075e-01 +-2.6074890748186752e-02 +-2.6291993428371780e+00 +5.6895565594323905e-01 +-2.9167044473940331e-02 +-2.7194946913334848e+00 +3.5552483562043985e-01 +-1.8592332887416352e-02 +-2.6595063691247827e+00 +4.1757347849095877e-01 +-1.4705122159289423e-02 +-2.6174254154374395e+00 +1.3328140612598767e+00 +-2.8392072455530683e-02 +-2.3540541143099185e+00 +3.5407265495302587e-01 +3.9655604745846083e-02 +-2.6565468319216605e+00 +5.2742202773300628e-01 +4.4119807465378073e-02 +-2.6708281520020103e+00 +5.2742202773300628e-01 +4.4119807465378073e-02 +-2.6708281520020103e+00 +4.6224042009441391e-01 +4.9246516341844543e-02 +-2.6455667427969960e+00 +3.7854867508575152e-01 +5.1851631935574086e-02 +-2.6428104530802559e+00 +1.8931291414636751e+00 +2.3788229460559421e-02 +-3.4388438196573592e+00 +1.7100122461129603e+00 +3.4361893563223174e-02 +-3.1249420558534555e+00 +6.9267351331591676e-01 +1.2094982502401012e-01 +-2.8485202193185071e+00 +5.0184295022361025e-01 +1.2708216633602992e-01 +-2.6527150129010253e+00 +8.8339566452001772e-01 +1.3073922095417470e-01 +-3.0411590195463929e+00 +4.8165822810160203e-01 +1.5909189810302601e-01 +-2.6477514241358895e+00 +4.1189803799334024e-01 +1.6794356843812305e-01 +-2.6589992397534994e+00 +4.7879540386551978e-01 +1.7209576447356068e-01 +-2.6586908562471137e+00 +5.8515990083083691e-01 +1.7973476851579295e-01 +-2.7337123428218795e+00 +7.0429802449026757e-01 +1.9646003280224719e-01 +-2.8586319490254715e+00 +7.0840969765245199e-01 +1.9642502416303276e-01 +-2.8651983124691722e+00 +7.5969126136193332e-01 +2.1219997369048191e-01 +-2.9205436152209554e+00 +4.1258905925517009e-01 +2.2590207201128693e-01 +-2.6628689245869941e+00 +4.1258905925517009e-01 +2.2590207201128693e-01 +-2.6628689245869941e+00 +6.9104951229346634e-01 +2.8013214927081043e-01 +-2.8461722697111633e+00 +7.2557240536920875e-01 +2.9034487406835152e-01 +-2.8716749188762614e+00 +3.3027274113239524e-01 +2.9457639496172611e-01 +-2.6448401214425377e+00 +3.9900493446621366e-01 +2.9632274452354079e-01 +-2.6440496941884777e+00 +3.7137885706890322e-01 +2.9758295690372127e-01 +-2.6568645188611142e+00 +3.7137885706890322e-01 +2.9758295690372127e-01 +-2.6568645188611142e+00 +3.4394514735213944e-01 +2.9790713378565487e-01 +-2.6507597606711450e+00 +3.1790301396673237e-01 +2.9600993904838124e-01 +-2.6411731030575005e+00 +4.0975816816686694e-01 +3.0563331808173810e-01 +-2.6628360093196348e+00 +3.7583153151648419e-01 +3.2534362225941982e-01 +-2.6643684103784242e+00 +3.7586295378139845e-01 +3.2534747756401933e-01 +-2.6644466830027551e+00 +4.2743463135234794e-01 +3.4398341753449252e-01 +-2.6575000832414362e+00 +4.2852555906476625e-01 +3.4417714876625183e-01 +-2.6597136109628003e+00 +1.9493289177353086e+00 +4.3721504195537159e-01 +-3.0215653220386218e+00 +3.9268316190752933e-01 +3.6442074236878319e-01 +-2.6647027211682119e+00 +1.9351894100478220e+00 +4.4702824812866987e-01 +-3.0077174034133805e+00 +1.9158160418426644e+00 +4.4812730427668146e-01 +-3.0552075013402900e+00 +1.8112562561817251e+00 +5.4707032509185904e-01 +-4.5500809123343178e+00 +4.3251037561094507e-01 +3.8099782584463165e-01 +-2.6421243937320820e+00 +3.5414928845451099e-01 +3.9184730427531755e-01 +-2.6624520808296297e+00 +3.5681888875696621e-01 +3.9499464490477754e-01 +-2.6517076989360508e+00 +4.6147068280213760e-01 +4.0635358502723445e-01 +-2.6748015580140803e+00 +3.6256834189035930e-01 +4.0947188057675571e-01 +-2.6643188266821403e+00 +2.4668700686876088e-01 +4.1481605593006932e-01 +-2.7238715086383278e+00 +3.7405100590058837e-01 +4.2432573236448906e-01 +-2.6680084373676065e+00 +3.0660923571666260e-01 +4.2590695394596167e-01 +-2.7070692537341214e+00 +1.9662605935333624e-01 +4.3324220571072836e-01 +-2.8052585584210563e+00 +-3.8591039666628862e-01 +1.9068792858148151e-02 +-6.5304434262078126e-01 +2.1229411761418140e-01 +-9.6419854067206351e-02 +-2.7484875664559327e+00 +2.1229411761418140e-01 +-9.6419854067206351e-02 +-2.7484875664559327e+00 +1.7632639195871666e-01 +-9.5209540490231712e-02 +-2.7527825842501836e+00 +7.9182168195499436e-01 +-6.5193777168330982e-02 +-2.9210606228964782e+00 +7.9182168195499436e-01 +-6.5193777168330982e-02 +-2.9210606228964782e+00 +7.8013339620715816e-01 +-5.8477227346655433e-02 +-2.9079150943164538e+00 +5.6085705646933148e-01 +-3.9871476100987235e-02 +-2.6999545824488220e+00 +5.5476654520267787e-01 +-3.9628007902625356e-02 +-2.7052221321922802e+00 +4.5730375810020629e-01 +-3.1185732517978303e-02 +-2.6282652846831649e+00 +4.7523347781587516e-01 +-3.2756644044556714e-02 +-2.6584136939973666e+00 +-4.5294227546753280e-01 +5.9152290134269932e-02 +-6.4390899390347833e-01 +8.0674558396123264e-01 +-2.6599998440012877e-02 +-2.9433588085692546e+00 +5.2651570732162223e-01 +3.1011721737024229e-02 +-2.6804276658014610e+00 +6.1251025315734153e-01 +3.0249188704326243e-02 +-2.7537299891039666e+00 +5.3817031639581736e-01 +3.4824718641494223e-02 +-2.6885193440557305e+00 +6.2019304519846696e-01 +3.8847819154035491e-02 +-2.7665056356674809e+00 +5.5847084459356910e-01 +4.5035162732181562e-02 +-2.7094362212714214e+00 +5.5199548210572569e-01 +5.1532880403459810e-02 +-2.6961774135585941e+00 +1.5979854516095418e+00 +4.7442565652937294e-02 +-2.9689452130766152e+00 +1.5439409014560508e+00 +5.1963780591460541e-02 +-2.8879025370653699e+00 +1.5745910304914061e+00 +5.0328032333912143e-02 +-2.9332696807115162e+00 +1.5251972682367150e+00 +5.4811305393666764e-02 +-2.8572670809083140e+00 +6.7620465431670096e-01 +7.1245566637921809e-02 +-2.8152057772285546e+00 +4.7476175228611017e-01 +7.8666537509684581e-02 +-2.6583108680463625e+00 +2.8922184800724787e-01 +8.5682449317500797e-02 +-2.6603874683736546e+00 +6.3139216989851676e-01 +8.5897755468164555e-02 +-2.7770024907496387e+00 +2.6466635675436556e-01 +8.9892994834812695e-02 +-2.6841009322025724e+00 +6.8119347763470284e-01 +9.6903914532394900e-02 +-2.8183735635149483e+00 +4.5485445623447662e-01 +1.0328355581150919e-01 +-2.6433798671963080e+00 +3.1932580174472852e-01 +1.0825443712958993e-01 +-2.6349153241444196e+00 +6.7673821935643330e-01 +1.1375621693413604e-01 +-2.8307577679448732e+00 +3.4935400468180167e-01 +1.2412019233095001e-01 +-2.6511024588326664e+00 +6.1593387058275884e-01 +1.4970031493364849e-01 +-2.7629900805904155e+00 +2.2284142462685468e+00 +1.7586546754648794e-01 +-3.9448305451712029e+00 +5.2914684383464827e-01 +1.6063011741344704e-01 +-2.6901947028974602e+00 +2.2860931943726115e+00 +2.1992001598240432e-01 +-4.0221137338943143e+00 +2.3378039096662846e+00 +2.2209133200019970e-01 +-3.9858924619257659e+00 +3.1304738800020282e-01 +2.1597464585556508e-01 +-2.6416195565455611e+00 +6.2710922617869369e-01 +2.2346924576552690e-01 +-2.7816009948796552e+00 +6.2710922617869369e-01 +2.2346924576552690e-01 +-2.7816009948796552e+00 +4.3282220637197028e-01 +2.1878700835159734e-01 +-2.6579063777417709e+00 +1.0280074558887504e+00 +2.5135048540337196e-01 +-3.2221951495770096e+00 +6.4591681753181984e-01 +2.4251296340510065e-01 +-2.7952347897248937e+00 +7.8020692791765955e-01 +2.8223345004694944e-01 +-2.9309522420315099e+00 +6.4136705120850868e-01 +2.7532667129616512e-01 +-2.7858271525736535e+00 +3.3123554335073474e-01 +2.6649491644493112e-01 +-2.6583314269674796e+00 +3.3751359166445477e-01 +2.7116976595274822e-01 +-2.6592953340017318e+00 +5.1361344263737529e-01 +2.7737015319544711e-01 +-2.6849766715905092e+00 +1.7204198297010378e+00 +3.3130757092026508e-01 +-3.1573239463687472e+00 +3.0989187925591477e-01 +2.9269826768661639e-01 +-2.6605417275575061e+00 +4.2502883550385306e-01 +2.9503881151244293e-01 +-2.6494891209912872e+00 +4.2818064308526022e-01 +2.9745796158900578e-01 +-2.6726467854553420e+00 +4.1599457502570275e-01 +2.9972594850985435e-01 +-2.6422765043759564e+00 +1.0019502534196307e+00 +3.7506135770730842e-01 +-3.3166420784358968e+00 +4.1892160808994505e-01 +3.2927541378423031e-01 +-2.6680732535700322e+00 +3.7556848813673277e-01 +3.3755922709216701e-01 +-2.6620541813833296e+00 +4.7994329605829761e-01 +3.5468113216592678e-01 +-2.6742061688483187e+00 +5.6167142613017895e-01 +3.7377533109013367e-01 +-2.7128043626515588e+00 +5.2877719362827369e-01 +3.7511162476283771e-01 +-2.6872469931343668e+00 +5.2877719362827369e-01 +3.7511162476283771e-01 +-2.6872469931343668e+00 +5.1198447585539619e-01 +3.8057147329208657e-01 +-2.6779312743387820e+00 +2.3588101450713533e-01 +3.7524294250294021e-01 +-2.7201270242891344e+00 +5.7338215328807818e-01 +4.0375150513582081e-01 +-2.7412998492481915e+00 +4.6538275489545189e-01 +4.1388499823838915e-01 +-2.6679568734275620e+00 +2.6872446111336418e-01 +4.1329869803498193e-01 +-2.7016838665765981e+00 +5.4798458811042849e-01 +4.2848757859906550e-01 +-2.7210898485509114e+00 +2.0283478193730753e+00 +5.1586110325339141e-01 +-3.0584373192844234e+00 +2.9715393361762904e-01 +4.2386029643482254e-01 +-2.6872725595010754e+00 +4.4956272812911929e-01 +4.3396883377931439e-01 +-2.6645762601018101e+00 +2.9697202604291745e-01 +4.4412048732515375e-01 +-2.6813415382477825e+00 +3.8934946932239900e-01 +4.5666390413984875e-01 +-2.6550966527553159e+00 +5.5027270442505338e-01 +4.7317087514569561e-01 +-2.7404308653053877e+00 +-4.2590620205040763e-01 +-8.4530991741944492e-03 +-6.3790619812086691e-01 +4.4754429857137468e-01 +-5.3009867021075102e-02 +-2.6341277197934825e+00 +3.1749103145988300e-01 +-4.2055295415741129e-02 +-2.4693227021021276e+00 +4.9261703438704363e-01 +-5.3387379623474125e-02 +-2.6349141653916255e+00 +5.1658300430320392e-01 +-5.4324546049004989e-02 +-2.6476157433804328e+00 +5.2275377143257518e-01 +-5.5149367952159863e-02 +-2.6724254545932031e+00 +6.0341300218180938e-01 +-5.4830782905955548e-02 +-2.7387356649737904e+00 +-4.3586724881096073e-01 +4.9676828690702932e-02 +-6.4448324652297784e-01 +5.3914526255615736e-01 +-4.3634122158240758e-02 +-2.6878285239530109e+00 +-4.5011729905012093e-01 +5.2728186209007072e-02 +-6.5355525788854141e-01 +4.4525804094258720e-01 +-3.4146784734721956e-02 +-2.6177163917736612e+00 +6.4033296733047040e-01 +-3.8657272340210484e-02 +-2.7789548742703203e+00 +4.3931297291653876e-01 +-2.7441285311210525e-02 +-2.6208592518640206e+00 +5.1409910759776589e-01 +-2.5768285133612772e-02 +-2.6602575748763111e+00 +6.1842586320439530e-01 +-2.7670755737315127e-02 +-2.7643521644662195e+00 +4.3408120742183198e-01 +-1.5431226796453156e-02 +-2.6185924934213474e+00 +6.1847251298355888e-01 +-1.9122149905886874e-02 +-2.7638299668750945e+00 +4.7066792042285488e-01 +3.8981481450319273e-02 +-2.6524995051219062e+00 +5.2648167777036192e-01 +3.9287448890765020e-02 +-2.6802743551081818e+00 +8.7581395483985858e-01 +2.9060687578858175e-02 +-3.0275705719851786e+00 +9.4667294740730867e-01 +3.0746962311081805e-02 +-3.1152304129766151e+00 +9.4667294740730867e-01 +3.0746962311081805e-02 +-3.1152304129766151e+00 +5.7570262099477032e-01 +4.5518017284485096e-02 +-2.7224512945244213e+00 +3.1388129017071015e-01 +5.3879875633813468e-02 +-2.6496260935140339e+00 +5.8465310835863149e-01 +7.4127645574943210e-02 +-2.7373583225216747e+00 +6.8631097992101076e-01 +7.9395719910298479e-02 +-2.8317900804069032e+00 +6.2000544935202551e-01 +8.8081851563320282e-02 +-2.7668364949128064e+00 +3.1380549303861727e-01 +9.3701363032212451e-02 +-2.6343884162112285e+00 +7.1770204582249775e-01 +9.0160941146475368e-02 +-2.8513887304128609e+00 +4.4257241960018123e-01 +1.0197165338541193e-01 +-2.6449617466964495e+00 +8.3525326231744623e-01 +1.0241919208629040e-01 +-2.9804846746891620e+00 +5.2974539492451900e-01 +1.1053574025012843e-01 +-2.6883383464288926e+00 +1.0440246725393389e+00 +1.1247774693154940e-01 +-3.2271927815213131e+00 +1.0440246725393389e+00 +1.1247774693154940e-01 +-3.2271927815213131e+00 +8.2140964783026527e-01 +1.2571447082406459e-01 +-2.9627106947118760e+00 +8.2347511090445891e-01 +1.2564166293899109e-01 +-2.9659381633089987e+00 +6.8860738037375180e-01 +1.2681231892246675e-01 +-2.8535349928735423e+00 +1.0214626799139728e+00 +1.3071057196654728e-01 +-3.1928240814297468e+00 +5.4545536226121094e-01 +1.4239471414465918e-01 +-2.6979174388873526e+00 +3.7926981227387319e-01 +1.5073036804590426e-01 +-2.6573779458812221e+00 +5.0951257293601282e-01 +1.5379292323121735e-01 +-2.6794025366210632e+00 +4.0956320055185119e-01 +1.5636964471900416e-01 +-2.6539677614776687e+00 +5.2174993089030053e-01 +1.7696025563227863e-01 +-2.6867537648642110e+00 +4.7352185021682969e-01 +1.8000668515789042e-01 +-2.6650816613060488e+00 +3.4698977013253579e-01 +1.7922837669826022e-01 +-2.6561013367794528e+00 +3.5303583266328165e-01 +1.8232982192546671e-01 +-2.6602341424082501e+00 +2.6865379452357291e-01 +1.8741821031280259e-01 +-2.6892356635079495e+00 +5.6135447926734339e-01 +1.9024143413119715e-01 +-2.7168576919552554e+00 +5.6374699122876359e-01 +1.9923688242364984e-01 +-2.7206592859661418e+00 +5.7218933590860033e-01 +2.1325298665806786e-01 +-2.7281327887041691e+00 +1.0518295639818827e+00 +2.4677581956066763e-01 +-3.2366320544026470e+00 +1.0327422812448586e+00 +2.6056688400516831e-01 +-3.2339815726981449e+00 +3.3053866629900192e-01 +2.3804607589093060e-01 +-2.6739146990447642e+00 +1.7454390534554696e+00 +2.7503784844082541e-01 +-3.1750642410949173e+00 +4.1295983033714218e-01 +2.4197132839479285e-01 +-2.6593119149073123e+00 +3.2537295804287003e-01 +2.4300363008930934e-01 +-2.6650104752599475e+00 +2.9959956861288123e-01 +2.4378073800599240e-01 +-2.6695848105883320e+00 +5.6366574098145406e-01 +2.5926089506097372e-01 +-2.7250172234589214e+00 +3.3822433147053788e-01 +2.6177988194797280e-01 +-2.6538660911599434e+00 +4.9521852126948829e-01 +2.6790453494617794e-01 +-2.6700635512209678e+00 +4.8225516498863030e-01 +2.6795215587849674e-01 +-2.6677314245255754e+00 +3.7546970622345271e-01 +2.6964213379553315e-01 +-2.6569190563711373e+00 +4.4116562363248674e-01 +2.9145492201052664e-01 +-2.6583361833185308e+00 +4.2767547342294276e-01 +2.9046915957660213e-01 +-2.6557497228023621e+00 +3.5787156452181867e-01 +2.9870588558123468e-01 +-2.6428600910427176e+00 +3.7884538988648608e-01 +3.3029771176776718e-01 +-2.6789766562079333e+00 +4.5965104883520691e-01 +3.3418823024896105e-01 +-2.6708034272466823e+00 +4.1097223384089060e-01 +3.3734406019401336e-01 +-2.6618410549676645e+00 +5.8409343095953692e-01 +3.4816615241704618e-01 +-2.7496853437025002e+00 +3.3461891099313362e-01 +3.3623207830193341e-01 +-2.6599772146692233e+00 +3.9586051363018626e-01 +3.4088317130661644e-01 +-2.6588366696055314e+00 +4.3010580960411088e-01 +3.5011054300923400e-01 +-2.6680601497499974e+00 +3.9448449644734346e-01 +3.5140856594989900e-01 +-2.6547706021168809e+00 +5.1626566151302233e-01 +3.5847520423910439e-01 +-2.6912931474894650e+00 +5.4109307975322329e-01 +3.6112883240679500e-01 +-2.7076363703941353e+00 +4.4968176206314275e-01 +3.6495619408323571e-01 +-2.6705930035668239e+00 +4.4968176206314275e-01 +3.6495619408323571e-01 +-2.6705930035668239e+00 +4.5186732132106366e-01 +3.6917538550637047e-01 +-2.6678339830969025e+00 +4.4921130829858769e-01 +3.7303354133152805e-01 +-2.6700608169837046e+00 +5.6583917039724785e-01 +3.8098691393081391e-01 +-2.7193891788416131e+00 +4.8774116243011861e-01 +3.7942345342675160e-01 +-2.6864309570424267e+00 +2.3761533497119161e-01 +3.7941156633636491e-01 +-2.7165644367617996e+00 +2.4094515814351877e-01 +3.8235723702578495e-01 +-2.7008667287648227e+00 +4.5019864124374720e-01 +3.8896425750311048e-01 +-2.6717140767935756e+00 +1.9420687217274255e+00 +4.7158274166122865e-01 +-3.0053895126312300e+00 +2.1994247880151011e-01 +3.8820318118886654e-01 +-2.7227962158510919e+00 +3.0848129065924385e-01 +3.9576765767154432e-01 +-2.6743799113550244e+00 +3.2658347325701209e-01 +3.9756970657166835e-01 +-2.6708493509895050e+00 +4.0637058749685218e-01 +4.0105381071260626e-01 +-2.6578329357187025e+00 +4.4382696230982704e-01 +4.0628918196532604e-01 +-2.6674266158089766e+00 +2.4943846839370679e-01 +4.0801749030673240e-01 +-2.7061005673358456e+00 +5.9989111990432664e-01 +4.4293963232245270e-01 +-2.7612087390810869e+00 +2.0179384050368879e-01 +4.3612763036663860e-01 +-2.7819969812160270e+00 +1.9002852725265670e-01 +4.4903821801377858e-01 +-2.7776369835756656e+00 +1.9002852725265670e-01 +4.4903821801377858e-01 +-2.7776369835756656e+00 +4.8884130857300523e-01 +4.5518556436393681e-01 +-2.6753386863820694e+00 +4.7086981618545021e-01 +4.5803143596615126e-01 +-2.6987499271226980e+00 +2.0811164544353641e-01 +4.5549465143069739e-01 +-2.7468673407644948e+00 +3.5283667470696689e-01 +4.5974398184967302e-01 +-2.6981691504704379e+00 +3.5713855092577607e-01 +4.5837645339499183e-01 +-2.6550517147488146e+00 +5.6192894594403875e-01 +4.7674363241732604e-01 +-2.7492759823117465e+00 +5.5740872825949794e-01 +4.7602635798356369e-01 +-2.7416481612064216e+00 +3.9591988397272088e-01 +4.6506212119501544e-01 +-2.6570494160599170e+00 +5.7167296904425491e-01 +-5.3583006586452223e-02 +-2.7061537098766686e+00 +5.5539876772657004e-01 +-4.2609450929059989e-02 +-2.6994359751406143e+00 +4.0175304590982192e-01 +-3.3794701851807087e-02 +-2.6137554364726325e+00 +4.8643979744902460e-01 +-3.5486090873440693e-02 +-2.6381151609205613e+00 +-1.3532105976801070e-01 +3.3219581652782486e-02 +-1.0981222527957291e+00 +6.0069169762593100e-01 +-2.9650493461673602e-02 +-2.7429706575155550e+00 +6.3500264454572719e-01 +-2.9550198379758426e-02 +-2.7814789416391066e+00 +-4.5586171970682804e-01 +6.1593038152722809e-02 +-6.4628001529112233e-01 +5.9791062005807738e-01 +-5.5535922499525391e-03 +-2.7386095794903316e+00 +4.5570324053419092e-01 +2.0359295698693217e-02 +-2.2213415415297120e+00 +9.6154023869757266e-01 +2.3645429304836915e-02 +-3.1250347870189596e+00 +8.4187638759703598e-01 +3.0270459855061535e-02 +-2.9881341850349146e+00 +5.7088227520672008e-01 +3.9141714667484707e-02 +-2.7205552556443346e+00 +4.5854802169690612e-01 +4.2467481818598302e-02 +-2.6395352016701752e+00 +3.6500358280331391e-01 +4.5817774765158498e-02 +-2.6230343221947132e+00 +1.5581920508796558e+00 +1.3672366007823466e-02 +-3.9192812394447341e+00 +4.1361127277451143e-01 +5.5110939722855849e-02 +-2.6311041292240227e+00 +1.5292665030335812e+00 +2.5237405841178992e-02 +-3.8821260033114027e+00 +6.4470519577232877e-01 +5.8967856016037608e-02 +-2.7906012229370165e+00 +6.5088045810696582e-01 +5.9034349875556121e-02 +-2.8005537718664804e+00 +7.8892987353011068e-01 +6.3720435940626624e-02 +-2.9269035348299597e+00 +3.9457795857587002e-01 +7.1747605140954906e-02 +-2.6240468896704878e+00 +3.7568395995252518e-01 +7.4542086933349683e-02 +-2.6335502921160625e+00 +5.9888156567345174e-01 +7.2794329313453421e-02 +-2.7434341437503620e+00 +4.0463766040806920e-01 +7.6562147381359386e-02 +-2.6501899063012671e+00 +3.7887961797093989e-01 +7.7040622683471532e-02 +-2.6261124495042716e+00 +3.0221936488710532e-01 +7.7879601973395371e-02 +-2.6408074044319192e+00 +3.6268630318008127e-01 +7.7516204789017412e-02 +-2.6297534131753286e+00 +3.5183923667219863e-01 +7.7892706392285876e-02 +-2.6213214549802109e+00 +3.5252709806280597e-01 +7.7725077441422680e-02 +-2.6331875806132841e+00 +3.3474366581820225e-01 +7.8017492357352780e-02 +-2.6293335944906744e+00 +1.8418811644381778e+00 +5.5662508959245252e-02 +-3.3195152361890856e+00 +3.1633451883937652e-01 +7.8593363041077210e-02 +-2.6279963732360714e+00 +6.4108845750608756e-01 +7.4231948256073432e-02 +-2.7843712682881061e+00 +9.9953002627467569e-01 +7.1770168671884502e-02 +-3.1812844831787452e+00 +7.3633980566350488e-01 +7.7984997755703153e-02 +-2.8732917806853666e+00 +4.7254456540878825e-01 +8.2985874417683528e-02 +-2.6659647948987897e+00 +7.7104369498707137e-01 +8.2019941430000881e-02 +-2.9028446945829343e+00 +3.9452393225725829e-01 +9.0010173607084729e-02 +-2.6434076596865301e+00 +1.5872111570964147e+00 +7.7038578292364310e-02 +-3.9527553857296240e+00 +6.6637176017139521e-01 +1.0049685723809036e-01 +-2.8146706542770343e+00 +7.9000787268284145e-01 +1.0018009790825251e-01 +-2.9276837082056786e+00 +5.5144618039255366e-01 +1.0386338861370860e-01 +-2.6996396890559580e+00 +5.2966636171896542e-01 +1.1664071939459721e-01 +-2.6886649704960219e+00 +6.4514164761697024e-01 +1.2059116867555189e-01 +-2.7907888178707592e+00 +7.8687206596417436e-01 +1.4812463914498325e-01 +-2.9235035187260419e+00 +3.7640857709635878e-01 +1.4766326014991638e-01 +-2.6463420971979326e+00 +4.1051827022346943e-01 +1.4998103516621367e-01 +-2.6436893312873200e+00 +6.0160472802300302e-01 +1.5168932929203330e-01 +-2.7492463281456949e+00 +5.5772510455651558e-01 +1.5150553205137401e-01 +-2.7111666346869967e+00 +5.1928781846820360e-01 +1.5132481761304992e-01 +-2.6858805328975546e+00 +5.8992066966341528e-01 +1.5280799507811127e-01 +-2.7412854363048158e+00 +5.4644113358006685e-01 +1.5449943284420384e-01 +-2.7007051511034654e+00 +5.1246450480079186e-01 +1.5622983386720898e-01 +-2.6752335760178565e+00 +9.5900173784279485e-01 +1.6545519634310846e-01 +-3.1412021829026053e+00 +6.0184871243043458e-01 +1.6154020075410783e-01 +-2.7489793534739286e+00 +3.9659297666140314e-01 +1.6299340266152465e-01 +-2.6315413213175880e+00 +3.5211631072297189e-01 +1.7149701044993476e-01 +-2.6668902037072573e+00 +6.1803774200668760e-01 +1.8460652919736539e-01 +-2.7757010426489219e+00 +2.6595706057780555e-01 +1.8307781369039874e-01 +-2.6970346482836631e+00 +3.6246912716581325e-01 +1.8459486254511140e-01 +-2.6541131060719692e+00 +5.5498609404342247e-01 +1.8739903716559092e-01 +-2.7129065755635628e+00 +3.5136778559839610e-01 +1.8855984694783634e-01 +-2.6574274611301405e+00 +5.5616674174182013e-01 +1.9525816990102945e-01 +-2.7146798016782125e+00 +5.5594064439565105e-01 +2.1042497904866628e-01 +-2.7140975175532014e+00 +7.9849453413465199e-01 +2.2658155335988339e-01 +-2.9424572032780483e+00 +4.3995021671261336e-01 +2.3649029705927282e-01 +-2.6632107759230297e+00 +6.2001424481824785e-01 +2.4878984947530236e-01 +-2.7741700940359753e+00 +7.7658873473563472e-01 +2.5702427081420448e-01 +-2.9125302777738393e+00 +4.8271929630041421e-01 +2.4571400460844109e-01 +-2.6677026713262380e+00 +3.7026246203579227e-01 +2.4649606656600997e-01 +-2.6540926299061836e+00 +4.0917524015703050e-01 +2.5144920937153270e-01 +-2.6446485621785558e+00 +1.7836634769914328e+00 +2.9477564975226456e-01 +-3.2272577539143361e+00 +5.2908646809602577e-01 +2.5937154027908710e-01 +-2.6905530779751525e+00 +7.9469949913225635e-01 +2.7314916105813147e-01 +-2.9448686200735219e+00 +4.4120529641836220e-01 +2.5941912368807568e-01 +-2.6561111054376108e+00 +4.8298489904406827e-01 +2.6098937807819567e-01 +-2.6631011360522123e+00 +4.8197414858954091e-01 +2.6363699643293359e-01 +-2.6684305149881404e+00 +3.2927403268702377e-01 +2.6173342734009264e-01 +-2.6715620268025799e+00 +4.9774663955832432e-01 +2.8855153324867983e-01 +-2.6611173640726924e+00 +4.6756227906526482e-01 +2.9009380154217979e-01 +-2.6536936064302443e+00 +1.7546542474890885e+00 +3.4168052966021562e-01 +-3.1531651765959325e+00 +2.8199941336771628e-01 +2.9225552030258739e-01 +-2.6564200955556321e+00 +6.1066944791740707e-01 +3.0560653920078562e-01 +-2.7697561462188314e+00 +4.3499353616423386e-01 +3.0398319418249981e-01 +-2.6606355197312772e+00 +4.3499353616423386e-01 +3.0398319418249981e-01 +-2.6606355197312772e+00 +4.2875446267427036e-01 +3.1212180175934440e-01 +-2.6527160753358618e+00 +4.2875446267427036e-01 +3.1212180175934440e-01 +-2.6527160753358618e+00 +5.5360285426412459e-01 +3.1836474069981524e-01 +-2.7133633823677781e+00 +5.5360285426412459e-01 +3.1836474069981524e-01 +-2.7133633823677781e+00 +4.5688673454884432e-01 +3.1429163307780827e-01 +-2.6655968876828151e+00 +4.4894051217027581e-01 +3.1654123257534811e-01 +-2.6588221264766450e+00 +4.5856564515551806e-01 +3.2297920202548669e-01 +-2.6914752306792282e+00 +4.4623119648878196e-01 +3.2092076490890992e-01 +-2.6489885924312055e+00 +2.3618366911316420e+00 +4.4523279260510223e-01 +-3.9607879841652673e+00 +4.2676073802122344e-01 +3.3216157609096986e-01 +-2.6756250228278846e+00 +2.3924077523465767e-01 +3.3611258465596833e-01 +-2.7025665563795527e+00 +3.7872523087564580e-01 +3.3969961980585661e-01 +-2.6510983138175668e+00 +3.8920869396197200e-01 +3.4098039586593953e-01 +-2.6605557963691191e+00 +4.4324444823548820e-01 +3.4520160596050664e-01 +-2.6599799409955498e+00 +4.4760903188275958e-01 +3.4788362320018640e-01 +-2.6620037262725171e+00 +4.4141840923301201e-01 +3.5491272975868260e-01 +-2.6513052954321998e+00 +2.7921995064454452e-01 +3.5281342658902032e-01 +-2.6838567047684112e+00 +5.7971302995014862e-01 +3.6890489331299470e-01 +-2.7307015128434822e+00 +5.9411084743683862e-01 +3.7226797450685251e-01 +-2.7454736025381625e+00 +5.8924207888479607e-01 +3.8529078603025330e-01 +-2.7438804387060860e+00 +1.7388164848365914e-01 +3.8085528315889378e-01 +-2.8222780058660777e+00 +3.4402029373316084e-01 +3.7730185349192841e-01 +-2.6528129049428166e+00 +3.0957289308181446e-01 +3.9314564615049807e-01 +-2.6658141535540532e+00 +4.5028316251968853e-01 +4.0347670241584960e-01 +-2.6709840055722172e+00 +4.5028316251968853e-01 +4.0347670241584960e-01 +-2.6709840055722172e+00 +4.7633304905694090e-01 +4.0568082815283174e-01 +-2.6792056507675066e+00 +2.5179528058238815e-01 +3.9723430856231740e-01 +-2.6798523571960247e+00 +6.2952257989789817e-01 +4.2748573015180746e-01 +-2.8004807495430666e+00 +2.5677648806271081e-01 +4.0688322903981800e-01 +-2.7049611386012584e+00 +5.9159687515990922e-01 +4.3909834281618626e-01 +-2.7543120999567559e+00 +5.9308467312183633e-01 +4.4443002479363952e-01 +-2.7569861864082306e+00 +2.5269757243664470e-01 +4.3013482970876621e-01 +-2.7224355131859679e+00 +5.2135956045951359e-01 +4.4842186329061379e-01 +-2.6998852111184837e+00 +6.0220628371270557e-01 +4.6217098449176719e-01 +-2.7649723758164018e+00 +4.7721798018629269e-01 +4.5480807240595217e-01 +-2.7024738100405683e+00 +5.0258733022780044e-01 +4.5813326212070415e-01 +-2.6815059624762982e+00 +2.0838475699311759e-01 +4.5202728749137416e-01 +-2.7508670893749345e+00 +2.7368364910328585e-01 +4.5239087339237039e-01 +-2.6894602081485939e+00 +3.4228847268921020e-01 +4.5976332694675315e-01 +-2.7000487183095827e+00 +2.6433347957695480e-01 +4.5735569466785314e-01 +-2.6814509459064118e+00 +2.6433347957695480e-01 +4.5735569466785314e-01 +-2.6814509459064118e+00 +2.5732701782411771e-01 +4.6303081480849889e-01 +-2.7388128986150657e+00 +1.9309685603457039e-01 +4.6145805628935044e-01 +-2.7597558313273973e+00 +3.9220575401423774e-01 +4.6749247532770039e-01 +-2.6572785297168942e+00 +4.2739033194780240e-01 +5.3117497234106359e-01 +-2.8136058761094711e+00 +4.2392597426574580e-01 +5.3344235150669161e-01 +-2.8139045900619597e+00 +4.6805706637583339e-01 +-5.6942756011965183e-02 +-2.6405757939250276e+00 +3.2686159894611255e-01 +-4.4508474097501631e-02 +-2.5918574153623992e+00 +1.0395798934467371e+00 +-8.4520383510013689e-02 +-3.2153164904874698e+00 +5.6131991605918041e-01 +-4.9972497753879144e-02 +-2.7087845918988438e+00 +5.9051562990385631e-01 +-5.1275060648282626e-02 +-2.7407269182759149e+00 +5.9433980210971826e-01 +-5.1261757636335017e-02 +-2.7467988067820932e+00 +5.8368126838051060e-01 +-4.9996311258867623e-02 +-2.7240539071659402e+00 +5.9197435538807541e-01 +-4.7225508352667901e-02 +-2.7375355230063207e+00 +5.7739329460537170e-01 +-3.7760243384942736e-02 +-2.7153641824383903e+00 +5.6879849930094972e-01 +-3.5868600082125099e-02 +-2.7210048057041551e+00 +4.8494775191570916e-01 +-3.1335360456713854e-02 +-2.6483055708650154e+00 +5.8700548912617301e-01 +-3.6038625657058614e-02 +-2.7243787674710918e+00 +7.8430949242227144e-01 +-4.0606025008071617e-02 +-2.9193388117743355e+00 +8.4216302999762538e-01 +2.2589492626666059e-02 +-2.9895891703750705e+00 +7.9968168719775878e-01 +2.4631758395030044e-02 +-2.9347007560156770e+00 +5.9393109245803788e-01 +3.3281483597778889e-02 +-2.7375977406339662e+00 +4.6011450620207234e-01 +5.1183933839053827e-02 +-2.6540705835537137e+00 +4.2670297219250475e-01 +5.1985324708322969e-02 +-2.6335806590510593e+00 +4.0906270269182848e-01 +5.2433597941781832e-02 +-2.6270445878348578e+00 +9.7725230890957926e-01 +3.8896330313147535e-02 +-3.1466624964634127e+00 +7.7651017294272440e-01 +5.9396156770382152e-02 +-2.9093114632778825e+00 +3.3934555492216179e-01 +7.3050922494704851e-02 +-2.6398999592615500e+00 +5.9078215491163510e-01 +7.0143940456438805e-02 +-2.7304816031067172e+00 +4.5859910474104243e-01 +7.5753722990253763e-02 +-2.6384948996379367e+00 +4.1083998799096733e-01 +7.6222459995984163e-02 +-2.6316195194102372e+00 +5.2788681904422596e-01 +8.5183315466381068e-02 +-2.6736856435106939e+00 +3.6005773300613436e-01 +8.8921846263624871e-02 +-2.6365993197088837e+00 +6.7434881370893363e-01 +8.7307003864985397e-02 +-2.8095621176921561e+00 +7.6449659785857849e-01 +8.7650966963434260e-02 +-2.8915992050570196e+00 +6.3050577074200587e-01 +8.9736184840654848e-02 +-2.7646535778307708e+00 +7.4783743149415305e-01 +9.6145185785256299e-02 +-2.8879489995751406e+00 +5.6335018079174326e-01 +1.0928395121295517e-01 +-2.7234910826022927e+00 +6.3622234365043939e-01 +1.1806435396987314e-01 +-2.7858892883247659e+00 +6.9795201659957062e-01 +1.2435559639228548e-01 +-2.8489006288269736e+00 +6.9811875744639118e-01 +1.2441423955500380e-01 +-2.8492350966343807e+00 +3.6337598973661062e-01 +1.3099843577177722e-01 +-2.6671697165129440e+00 +3.6337598973661062e-01 +1.3099843577177722e-01 +-2.6671697165129440e+00 +5.4790358811727236e-01 +1.4964236253476029e-01 +-2.7037258003414451e+00 +5.1695108932789313e-01 +1.8962915657430252e-01 +-2.6875757112403540e+00 +5.8071227988055252e-01 +2.0339579767827307e-01 +-2.7412252532854859e+00 +1.8701170178922799e+00 +2.6966168151579367e-01 +-4.4157593009810210e+00 +1.8747089026854595e+00 +2.8822460919547299e-01 +-4.3921762700277522e+00 +6.4392318440272900e-01 +2.3212061687398658e-01 +-2.7946895923805797e+00 +6.2708777967308083e-01 +2.3365052765964076e-01 +-2.7813066740119652e+00 +5.7257874299116640e-01 +2.4905367227905670e-01 +-2.7304161074424775e+00 +7.5352224378855692e-01 +2.6405358359741754e-01 +-2.9036061527106884e+00 +5.3975348885733676e-01 +2.5372626222528799e-01 +-2.6988584969249168e+00 +7.7095278022859404e-01 +2.7043782484884249e-01 +-2.9270323283736692e+00 +7.0588519868056077e-01 +2.6984757324147718e-01 +-2.8547123035660813e+00 +7.2377225024514769e-01 +2.7061926341907422e-01 +-2.8824104740365657e+00 +5.2207583156196435e-01 +2.6118711790620297e-01 +-2.6846256095922536e+00 +6.9723758982019912e-01 +2.7126836481815891e-01 +-2.8517834324763274e+00 +7.2152165589647188e-01 +2.7609607404011910e-01 +-2.8788521376868199e+00 +5.1491877957429644e-01 +2.7659621383439315e-01 +-2.6792450551118492e+00 +5.1491877957429644e-01 +2.7659621383439315e-01 +-2.6792450551118492e+00 +4.6542261102781557e-01 +2.9482503251524889e-01 +-2.6473081360036161e+00 +4.4772006369600059e-01 +3.1604586439133880e-01 +-2.6815564911762211e+00 +4.5093564259099350e-01 +3.3654695976482740e-01 +-2.6594455386001910e+00 +3.3076091647000250e-01 +3.3909190260022987e-01 +-2.6603627489831405e+00 +4.4419545608437017e-01 +3.5479935563250981e-01 +-2.6616043910786669e+00 +4.5764164698643467e-01 +3.7457992524334560e-01 +-2.6550651147123991e+00 +4.0119166632690484e-01 +3.7686559383974583e-01 +-2.6545504918246148e+00 +4.2873721360550643e-01 +3.9463067009264063e-01 +-2.6531111853786400e+00 +6.2867151878283234e-01 +4.1355005558068852e-01 +-2.7933266815755764e+00 +2.2139849588525173e-01 +3.9861218755481503e-01 +-2.7414827289267980e+00 +2.2251128965343098e-01 +3.9861778586095920e-01 +-2.7328811126301535e+00 +2.2148106489892938e-01 +3.9842564524048135e-01 +-2.7306813427304055e+00 +3.2264495500794782e-01 +3.9888767246393025e-01 +-2.6777007049706452e+00 +2.2112470516103347e-01 +4.0088632424055365e-01 +-2.7355203769963419e+00 +2.2098262026824650e-01 +4.0085842430111174e-01 +-2.7352840225998336e+00 +2.3171410688309343e-01 +4.0177019240397260e-01 +-2.7245281106237655e+00 +2.3149786452647220e-01 +4.0172778082215754e-01 +-2.7242303086839366e+00 +2.2129354368927381e-01 +4.0327733822276107e-01 +-2.7303249184601004e+00 +2.3265661163732682e-01 +4.0344719187689765e-01 +-2.7209368524620476e+00 +2.2489987513457652e-01 +4.0556485499109296e-01 +-2.7322660990944097e+00 +3.1965066469678333e-01 +4.0564656829250084e-01 +-2.6719252058397105e+00 +2.2952959423907132e-01 +4.0628465407886011e-01 +-2.7311837540029242e+00 +2.3055909218215448e-01 +4.0639053918750107e-01 +-2.7330189041375910e+00 +4.8161733889999409e-01 +4.3126220657434439e-01 +-2.6849312763016755e+00 +3.9461457793333410e-01 +4.4255454964738028e-01 +-2.6797418848349372e+00 +5.9847724933612079e-01 +4.7726470333570625e-01 +-2.7854946339638520e+00 +4.0088168536024754e-01 +4.6679491778295118e-01 +-2.6566487194739081e+00 +9.1792701576058566e-01 +-9.3639988375719574e-02 +-3.0695479163024024e+00 +5.8926880151855321e-01 +-3.5841258977851495e-02 +-2.7337669816795698e+00 +7.7867967839770802e-01 +-3.7846307238898577e-02 +-2.9152303148900138e+00 +5.2783628079739286e-01 +-2.3255609902532965e-02 +-2.6631652849770555e+00 +7.7037414942580518e-01 +-3.5659054702299443e-02 +-2.8981697042201331e+00 +5.5111724275262663e-01 +8.6033984022624535e-02 +-2.7017518349371676e+00 +3.3731312956419657e-01 +9.0721075885126068e-02 +-2.6411875563467242e+00 +1.5285097637107565e+00 +8.1055488279412100e-02 +-3.8798801569194232e+00 +7.9484347983010983e-01 +1.0900563320568997e-01 +-2.9365695432815517e+00 +5.9891516987514637e-01 +2.1294993894853054e-01 +-2.7546189450131919e+00 +5.5954365630842728e-01 +2.2607969532857453e-01 +-2.7202924541740536e+00 +7.3550985124561463e-01 +2.7330799347414703e-01 +-2.8966282060575512e+00 +1.7562359718136091e+00 +3.2073387338715603e-01 +-3.1414103561268472e+00 +5.9419713815724928e-01 +3.2041638872572176e-01 +-2.7538135855257591e+00 +3.2952062464173548e-01 +3.2395927740447561e-01 +-2.6590108487111870e+00 +1.5170086144622443e+00 +3.5768807730945534e-01 +-2.5207877261692784e+00 +1.5131037016797804e+00 +3.5755434603158953e-01 +-2.5234701483956399e+00 +4.7075589355482539e-01 +4.0223691449301796e-01 +-2.6744059804265548e+00 +5.2477530870296496e-01 +1.1533568980391753e-01 +-2.6776750517409837e+00 +6.4304861799670709e-01 +-7.1036987397416707e-02 +-2.7867926235206548e+00 +6.8227063864295334e-01 +1.9106858694612006e-01 +-2.8446341100527102e+00 +5.4169942124692583e-01 +1.8682231677223607e-01 +-2.7003145932528598e+00 +5.8177224743059430e-01 +-9.6963185389217832e-02 +-2.7453069177050846e+00 +6.2019573084465873e-01 +-4.2988598791229383e-02 +-2.7712401641806550e+00 +1.0267719486456077e+00 +-4.5774179233619566e-02 +-3.2156149808209586e+00 +1.0231027420713754e+00 +-3.3221979330791990e-02 +-3.2090582315563281e+00 +1.5441779118434866e+00 +9.8734178059932037e-02 +-3.9204239082471686e+00 +7.1031926003773405e-01 +-5.7780456005204386e-02 +-2.8579700755916582e+00 +1.5230304519237443e+00 +7.2417386719151336e-02 +-3.8925526683124465e+00 +1.0414902973311144e+00 +2.3694203518232659e-01 +-3.2339119667265877e+00 +5.7394210657142908e-01 +-6.9993845256165324e-02 +-1.8866331539621173e+00 +1.2340051479471255e+00 +2.2706064674920354e-02 +-3.4975670966713919e+00 +1.5370168467099992e+00 +4.2204958899154647e-02 +-3.8937194002773547e+00 +4.7545632100219271e-01 +8.2866028309914089e-02 +-2.6713641969915756e+00 +1.0258526751529053e+00 +1.7858558843564576e-01 +-3.2211610243058555e+00 +1.8622101971026781e+00 +3.4281135119827927e-01 +-4.4606303442126860e+00 +8.0319176397560776e-01 +2.6123021080756337e-01 +-2.9508374112674312e+00 +2.2954059348478308e+00 +2.0770571044977668e-01 +-4.0612737446741844e+00 +1.6302342400412819e+00 +-7.4679587756459886e-02 +-3.9953541296034998e+00 +4.7194414275994330e+00 +-6.8356447559828157e-02 +-8.7834093926330503e+00 +4.7194414275994330e+00 +-6.8356447559828157e-02 +-8.7834093926330503e+00 +4.6923472714873178e+00 +-1.2039094438624892e-02 +-8.7361744071766196e+00 +-1.1971067526966255e+00 +8.7462169860663830e-01 +-2.4900338117858496e+00 +-1.2192413659280537e+00 +7.2232999248244112e-01 +-2.4444310227160546e+00 +5.9569014386373720e-01 +4.4584960503671611e-01 +-2.8095927089485362e+00 +8.3385728740885512e-01 +2.5683232955289725e-01 +-2.9983860472288018e+00 +1.0933443245761458e+00 +2.4756441583177022e-01 +-3.3758568904881741e+00 +1.1925586884301882e+00 +3.4065460295400618e-01 +-3.7067453447803174e+00 +1.0117378924363603e+00 +3.7328487429812679e-01 +-3.3156840299680912e+00 +-1.2581746793860491e+00 +1.7181205036026137e-01 +-2.3508861945984867e+00 +8.4443118349173762e-01 +3.9846564975813220e-01 +-3.1807383449400870e+00 +-1.9905855978434514e-01 +6.3176853610623973e-01 +-3.7316296984242401e+00 +-1.4186793621720590e+00 +1.0694245973677576e-01 +-2.4022169371370139e+00 +1.2425469979973769e+00 +2.1481641132743393e-01 +-3.5503328003852674e+00 +1.3088382192690213e+00 +2.2586772824506710e-01 +-3.6149485335829210e+00 +3.5777562983483041e-01 +2.7848922514002900e-01 +-2.6637516434078079e+00 +-1.0856406944463497e+00 +3.4694240531210113e-01 +-2.3980332789391343e+00 +9.7914341076062916e-01 +3.2676020509443565e-01 +-3.1814957904776779e+00 +6.6667716504059926e-01 +4.2860656015765419e-01 +-2.9149702527040158e+00 +-1.2228370375746267e+00 +6.6967955787223743e-01 +-2.4118709030714949e+00 +-1.3764277306212616e+00 +7.3842354381658515e-01 +-2.4637448445282715e+00 +1.8311904089834843e+00 +5.5739239822137063e-02 +-4.3715338943372153e+00 +1.7371924358063322e+00 +9.1134615566980215e-02 +-4.1870243895824970e+00 +1.7828313306464203e+00 +1.1347375228961648e-01 +-4.2605789374421850e+00 +-1.4950353467483992e+00 +2.9485766897554394e-01 +-2.4502880219969332e+00 +9.8530018451560741e-01 +2.6179105292825056e-01 +-3.1768177250988816e+00 +1.3831940415103174e+00 +2.5067490444567597e-01 +-2.5644139127730234e+00 +7.6275761915905171e-01 +2.8121000510257166e-01 +-2.9234325160724124e+00 +8.0918549669822881e-01 +3.0744899816785282e-01 +-2.9952842996531985e+00 +7.4767539822893836e-01 +3.8971010543400697e-01 +-3.0991930019046685e+00 +7.4577439079829466e-01 +3.8894495615156333e-01 +-3.0917637709186336e+00 +-1.3724265288590713e+00 +6.6059086726388494e-01 +-2.4143714510310454e+00 +-1.3562085954226215e+00 +6.9900669163592766e-01 +-2.4660237471139084e+00 +1.3767015018096611e+00 +1.0591371492575792e-01 +-3.7113800806773605e+00 +1.3156807220403959e+00 +1.5647093183067837e-01 +-3.6347530754077795e+00 +1.2733885256338175e+00 +1.6137884359231547e-01 +-3.5711719777089783e+00 +7.2608715610815766e-01 +2.3397420059770915e-01 +-2.8566408884035819e+00 +7.2608715610815766e-01 +2.3397420059770915e-01 +-2.8566408884035819e+00 +8.9322388349531767e-01 +2.4503430578802404e-01 +-3.0874094912193266e+00 +8.9322388349531767e-01 +2.4503430578802404e-01 +-3.0874094912193266e+00 +7.8845845591083985e-01 +2.4458850816499741e-01 +-2.9414550310608938e+00 +-1.4288837380008017e+00 +2.9287868492950780e-01 +-2.4300909716672616e+00 +3.1716622723911887e+00 +4.1149137479827874e-01 +-7.0902533745153669e+00 +9.0980639255650531e-01 +3.3793905394978430e-01 +-3.0714916988621979e+00 +3.1462605148029512e+00 +5.7898866439729613e-01 +-7.1194986459129606e+00 +5.7186396307510312e-01 +4.2066791860446873e-01 +-2.7327379088361234e+00 +-1.3138316632378608e+00 +4.8890580674700729e-01 +-2.3921600215171859e+00 +-1.0056809320225313e+00 +6.7334339138800903e-01 +-2.4301416332209573e+00 +-9.9183374920279821e-01 +7.0358125531200932e-01 +-2.4346408803782915e+00 +-9.9183374920279821e-01 +7.0358125531200932e-01 +-2.4346408803782915e+00 +1.7256106690175090e+00 +-6.2744375661927948e-02 +-4.1841769365241834e+00 +3.7283170336857557e-01 +3.5353529321652352e-02 +-2.6519225944965075e+00 +-1.4513450851196683e+00 +1.0358954803603226e-01 +-2.3991232831089762e+00 +3.7344801265773470e-01 +1.0049952418891740e-01 +-2.6581994837303236e+00 +1.6978105111527151e+00 +1.0760951052024778e-01 +-4.1389863255941082e+00 +-1.4357219738196634e+00 +2.1203373413779694e-01 +-2.4098835683920115e+00 +1.3129613286767936e+00 +2.0477855480532275e-01 +-3.6271630606635044e+00 +-1.4337931317394270e+00 +3.0863043352946307e-01 +-2.4075685801005489e+00 +9.2118166180315386e-01 +2.8415235276526668e-01 +-3.1003462484362343e+00 +7.1885477212608417e-01 +2.8349354688120471e-01 +-2.8589916250016723e+00 +7.2800920854400430e-01 +2.9949660898085534e-01 +-2.9116865260516658e+00 +9.1477267612058266e-01 +3.2290717992081897e-01 +-3.0742786279275212e+00 +3.1525331893971016e+00 +5.7624018887142581e-01 +-7.0295997277005471e+00 +-1.3771295351335757e+00 +4.3398230679553740e-01 +-2.4205456814759998e+00 +-1.3771295351335757e+00 +4.3398230679553740e-01 +-2.4205456814759998e+00 +7.9002595678530052e-01 +4.1599451387184339e-01 +-3.1808310676407077e+00 +5.8748613911558367e-01 +4.0916897157776611e-01 +-2.7584458383622907e+00 +-1.4039815998126690e-01 +5.1492473470382383e-01 +-3.5448890654896950e+00 +-1.4472637761054183e+00 +4.9347802310318506e-01 +-2.4221880115532270e+00 +-1.1777760570085900e+00 +7.9403659850402108e-01 +-2.4358459817907820e+00 +-1.1316799008322069e+00 +8.1050457315501589e-01 +-2.5221258074700774e+00 +1.7842574173103560e+00 +2.1063958847325408e-02 +-4.2651219025958138e+00 +8.7352971509147292e-01 +5.7262231429094874e-02 +-3.0513039956579786e+00 +-1.2746969156654075e+00 +1.5221676477957605e-01 +-2.3769638425762953e+00 +1.6643470948009873e+00 +9.4265022177799362e-02 +-4.0771448115599309e+00 +1.0133950780590417e+00 +1.6021654810770500e-01 +-3.2224217785384410e+00 +8.0195162828875111e-01 +1.6894145159471283e-01 +-2.9209240161166332e+00 +1.2734682484031690e+00 +1.9481153915350569e-01 +-3.5649336209212161e+00 +7.7273943395455758e-01 +1.9820784155032076e-01 +-2.9218197403421686e+00 +-1.4381112819984256e+00 +2.9173676876900029e-01 +-2.4113740371274166e+00 +9.6492073314870019e-01 +2.5975667667699981e-01 +-3.1548967218909389e+00 +8.2240949471353297e-01 +2.5897298275466357e-01 +-2.9694030648427194e+00 +-1.3352683474620122e+00 +3.1760160193138026e-01 +-2.4020703614457202e+00 +6.8203040334170817e-01 +3.0288152702721532e-01 +-2.8783585180949425e+00 +-7.3182625964469961e-01 +3.7508152020821883e-01 +-2.8339272215185485e+00 +1.0431964904293742e+00 +3.7125261164756312e-01 +-3.3422854026650075e+00 +5.8767990507228485e-01 +4.3303521161509761e-01 +-2.7560417530649799e+00 +-1.3631620654983883e+00 +5.5927613204651583e-01 +-2.3943618130036768e+00 +-1.4661861800424649e+00 +6.7985056594916804e-01 +-2.4462435377827876e+00 +-1.0392537529325683e+00 +6.5216848571678243e-01 +-2.4122436734748205e+00 +-1.3350263229484776e+00 +6.7858332879795302e-01 +-2.4308838416657603e+00 +-1.3250459158348602e+00 +6.7402780832128517e-01 +-2.4065837706783331e+00 +-9.7863556751425307e-01 +6.6913328918068604e-01 +-2.4372573328104061e+00 +-1.4449308454262835e+00 +7.1269593248179963e-01 +-2.4429895771475865e+00 +1.1534526075700087e+00 +-1.1160311317931951e-01 +-3.3551749990752846e+00 +-1.3872726127768980e+00 +6.6473119310964349e-02 +-2.3911043321986347e+00 +-1.3876522398112257e+00 +7.4557989836940897e-02 +-2.3863699885022633e+00 +1.3448534705900614e+00 +3.8816840015396786e-02 +-3.6537598721451223e+00 +8.7210473075620776e-01 +9.6289122648057668e-02 +-3.0478921333874096e+00 +1.3484185265771462e+00 +1.0983900315861464e-01 +-3.6600855058452990e+00 +1.2301220230747845e+00 +1.2154675154407076e-01 +-3.5205529302790435e+00 +-1.4544556693898265e+00 +1.8839205093222866e-01 +-2.4060516941481360e+00 +-1.4752301083881620e+00 +2.2943904319237943e-01 +-2.4256881272830113e+00 +8.7407084585783534e-01 +1.8918405254543860e-01 +-3.0421023441149773e+00 +8.1368724174083673e-01 +2.1014597250011857e-01 +-2.9676602896236619e+00 +8.7687425861675572e-01 +2.1572643485453050e-01 +-3.0456894702772410e+00 +1.0722651826019380e+00 +2.5024816261638377e-01 +-3.2484892726544206e+00 +2.9850697599504668e+00 +3.7828563414137539e-01 +-6.9523213459474809e+00 +-1.4684105474201328e+00 +3.3035207853726706e-01 +-2.4265958972062398e+00 +1.7874874730303818e+00 +3.6892452669616210e-01 +-4.5620909693060749e+00 +6.7794595304019412e-01 +3.3969826903217415e-01 +-2.8986202539717238e+00 +-1.5373197282082522e+00 +4.0232059492841893e-01 +-2.4490846889680800e+00 +-1.5058194434382515e+00 +4.2117058845844285e-01 +-2.4331946254987424e+00 +-1.4795938941003783e+00 +4.1906178056784388e-01 +-2.4214071496660421e+00 +-1.1222138530187480e+00 +4.1494426970357839e-01 +-2.3876717808081502e+00 +-1.5213993145941396e+00 +4.3527970809840377e-01 +-2.4337302927287854e+00 +-1.3303235341800741e+00 +4.3649190352215933e-01 +-2.3786667928451326e+00 +-1.2056957049113584e+00 +4.3877765623119191e-01 +-2.3941179202602485e+00 +-2.6192539492759731e-01 +5.0759367838850367e-01 +-3.7090741701494938e+00 +-1.4400232576941452e+00 +4.7587965696925938e-01 +-2.4278824005038127e+00 +-1.7133566272965123e-01 +5.5052422995943695e-01 +-3.6497126914913411e+00 +-1.3495446961444897e+00 +4.9203801534194136e-01 +-2.3879375812967170e+00 +6.1395818635242705e-01 +4.6021988247100598e-01 +-2.8010609431790798e+00 +-1.3253813514996973e+00 +5.1639442361924659e-01 +-2.4096318828439514e+00 +-1.4195686787379549e+00 +6.3175575651845106e-01 +-2.4285969191702463e+00 +-1.2915573747274101e+00 +6.2252596533085558e-01 +-2.4024845609246643e+00 +-9.1894035293576581e-01 +6.1597537170657379e-01 +-2.4748403131144143e+00 +-8.6331806345192807e-01 +6.1922063501966373e-01 +-2.5004304376116058e+00 +-1.0813822503400177e+00 +6.2847521328344957e-01 +-2.4106514903589984e+00 +-8.7788090002339858e-01 +6.6684311254590645e-01 +-2.5077780211385980e+00 +-8.8941331778158461e-01 +6.8434787570776245e-01 +-2.5063050045311992e+00 +-1.1298956668731412e+00 +9.0879560419401040e-01 +-2.6231847049686383e+00 +1.0736067792841839e+00 +-7.9577909214359629e-02 +-3.2975650091195257e+00 +-8.5464060233105599e-01 +2.1560515321744727e-02 +-2.5644365678439964e+00 +1.2030214385015920e+00 +-1.4856442066664583e-02 +-3.4787306271317515e+00 +-1.2464622239766088e+00 +8.9271118527013207e-02 +-2.3530228606433194e+00 +9.8158841518956697e-01 +3.7990969419783367e-02 +-3.1893880003294810e+00 +1.3406106141718015e+00 +2.8571513603300319e-02 +-3.6404794090270265e+00 +1.7921940598436199e+00 +3.9143228456514849e-02 +-4.2724248507454226e+00 +1.3346331443549895e+00 +6.6839167140957167e-02 +-2.3888308604843829e+00 +-1.1411354501500734e+00 +1.3804822760606020e-01 +-2.3770180689289160e+00 +-1.1406993806764214e+00 +1.4800122424550224e-01 +-2.3761214190716786e+00 +-1.1410399996526288e+00 +1.4034105982540182e-01 +-2.3758676550591229e+00 +8.1538254588508974e-01 +1.5836350375778629e-01 +-2.9534149136450982e+00 +-1.2475957904736346e+00 +2.0248551292229555e-01 +-2.3593681711437817e+00 +-1.2367233492448853e+00 +2.0752100446740146e-01 +-2.3671504701057811e+00 +8.6701536840138205e-01 +1.7132304998746686e-01 +-3.0398846133114001e+00 +-1.1395383985394645e+00 +2.2380099476939125e-01 +-2.3810094852943582e+00 +1.0336415629099838e+00 +1.9026270309156246e-01 +-3.2424763027925123e+00 +-1.4666763704271222e+00 +2.3990043159338734e-01 +-2.4183595192308607e+00 +8.6919601047691653e-01 +1.9423800755769513e-01 +-3.0434237370482387e+00 +-1.4671560857310695e+00 +2.6683211306293736e-01 +-2.4210190812263450e+00 +7.7155054230111664e-01 +2.3717477054082448e-01 +-2.9259538983357380e+00 +8.9585203284413972e-01 +2.4634387988183623e-01 +-3.0758287159810016e+00 +9.4816834630436808e-01 +2.6058262698033358e-01 +-3.1461789169919192e+00 +1.0431566836659070e+00 +2.8541780682613871e-01 +-3.2927245987072378e+00 +3.0633824934078002e+00 +4.1336167721468969e-01 +-6.9544646307138187e+00 +-1.3164355542031270e+00 +3.4441983171118840e-01 +-2.4143172488211166e+00 +6.6746445291438972e-01 +3.4106641361819401e-01 +-2.8788767832714255e+00 +1.3077497574324726e+00 +3.7672901365206152e-01 +-3.7139559814740775e+00 +-1.1564896914851606e+00 +4.0789191839932692e-01 +-2.3690019455480682e+00 +-1.3859362612878050e+00 +4.2236973566466540e-01 +-2.4106245728757036e+00 +-1.4305881134151861e+00 +4.4073947054811824e-01 +-2.4195770378761381e+00 +7.1946508021233513e-01 +4.1224084051201082e-01 +-3.0327125950275406e+00 +-1.3208126224019228e+00 +4.3743431867644977e-01 +-2.3911298608964353e+00 +-1.3082499192617569e+00 +4.5457676357829108e-01 +-2.3858029625485515e+00 +-1.3094619351600609e+00 +4.5538228377108853e-01 +-2.3958686810469958e+00 +-1.1229989697453227e+00 +4.6285298610553238e-01 +-2.3841099257928668e+00 +-1.1375135994845009e+00 +4.6518940903482969e-01 +-2.4014899102012288e+00 +5.4747682255210783e-01 +4.4913727429585143e-01 +-2.7436385404123280e+00 +5.7970409403178080e-01 +4.5235028891851231e-01 +-2.7330996891587516e+00 +5.8064300340299857e-01 +4.5960315061140611e-01 +-2.7409813856003846e+00 +-1.1406675942383457e+00 +5.5266373548177239e-01 +-2.3916158165317438e+00 +-1.4042869983378174e+00 +6.2711812183831761e-01 +-2.4340621653535348e+00 +-1.3679280908360367e+00 +6.2249862921412658e-01 +-2.4004597172721485e+00 +-1.2644824970098167e+00 +6.2505787125161361e-01 +-2.4159972234790601e+00 +-1.2715558274071492e+00 +6.2205577614975682e-01 +-2.3947750925876194e+00 +-1.2260253259548637e+00 +6.2232216839959786e-01 +-2.3982031491155062e+00 +-1.0128416961381161e+00 +6.2488307889809047e-01 +-2.4147281388452462e+00 +-9.1908862804623037e-01 +6.3248227813025160e-01 +-2.4691541286380270e+00 +-9.6322641605708104e-01 +6.3455630490338455e-01 +-2.4437222540780241e+00 +-8.5391349970451413e-01 +7.1292807506028377e-01 +-2.5745145447528777e+00 +-1.2737205408301266e+00 +7.4653657310180677e-01 +-2.4267195886248252e+00 +-1.1794962545293797e+00 +7.5884940770942699e-01 +-2.4290994561009573e+00 +-1.1755650901603878e+00 +7.6539126093205534e-01 +-2.4275134079295850e+00 +-7.6060666539737076e-01 +8.9352523157732866e-01 +-2.9942237714353963e+00 +-8.7064383784808441e-01 +9.2213723339285114e-01 +-3.0748884974840354e+00 +1.0669417502429677e+00 +-1.3278276249059970e-01 +-3.2576542524491177e+00 +9.4538127093859980e-01 +5.4147079948149864e-04 +-3.1420528449615182e+00 +-1.2718287141425613e+00 +9.3552640567000134e-02 +-2.3718675684540003e+00 +9.7475967410001962e-01 +4.3800090936670116e-02 +-3.1815749440658339e+00 +-1.1408999685200607e+00 +1.6623752897894709e-01 +-2.3775871759818203e+00 +-1.4274156224820025e+00 +2.1585359045874974e-01 +-2.4161348944007717e+00 +1.2827537487588714e+00 +1.8676652535763599e-01 +-3.5817386643298690e+00 +7.9570859214063561e-01 +1.9571563465521424e-01 +-2.9242736280617230e+00 +-1.2028979537412658e+00 +2.6344304646614769e-01 +-2.3734180873183934e+00 +1.3721599770378938e+00 +2.0998214131269513e-01 +-2.5520080377955798e+00 +7.3534088640930173e-01 +2.5458204226094022e-01 +-2.8847597060039107e+00 +1.3853703965562743e+00 +2.3037278411167109e-01 +-2.5513272639655371e+00 +7.5570178353873974e-01 +2.6448234064605358e-01 +-2.9102537395543440e+00 +1.0314051130537680e+00 +2.7390916165036194e-01 +-3.2392828495133346e+00 +3.0083314262001788e+00 +4.2683839605846741e-01 +-6.9230024951989151e+00 +9.5634173629749797e-01 +3.2041865622278015e-01 +-3.1310002995326420e+00 +7.7521840725743729e-01 +3.9083573765043833e-01 +-3.1748323717113753e+00 +6.8314970927837482e-01 +3.7805012952456990e-01 +-2.9107654009989457e+00 +-3.3490699017394404e-01 +4.8991870197138704e-01 +-3.8791588926012133e+00 +-1.2634819239632156e+00 +4.4684623091172315e-01 +-2.6215803961206761e+00 +5.5640482473305564e-01 +4.0967513327873289e-01 +-2.7148878319008349e+00 +-1.3185046873824728e+00 +4.6032709246118891e-01 +-2.3981195520840757e+00 +-3.3275259587851419e-01 +5.5886147466773339e-01 +-3.8542427617754775e+00 +-1.4236041816327474e+00 +5.0189516241845189e-01 +-2.4223369774584658e+00 +4.2825603013559999e-01 +4.5597120913044964e-01 +-2.6559312883023911e+00 +-1.7680672319292434e-01 +5.9573279679107116e-01 +-3.7276653417346175e+00 +-1.3320755310471957e+00 +5.1908495363634344e-01 +-2.4108933021745407e+00 +-1.1793366204820346e+00 +5.1505029032374283e-01 +-2.3835579821920567e+00 +-1.0006537253169330e+00 +5.1124212554845316e-01 +-2.4175031080462084e+00 +-1.3426367891103002e+00 +5.4836032003388169e-01 +-2.3824257238163660e+00 +-1.2791346018174372e+00 +5.2102433612437882e-01 +-1.5467426138931408e+00 +-1.3769046525846853e+00 +6.3773827650546078e-01 +-2.4045034529924294e+00 +-1.3365211501529557e+00 +6.4588327152333491e-01 +-2.4274734458147842e+00 +-1.4558584065040570e+00 +6.7428650602457207e-01 +-2.4391098126945669e+00 +-1.3104059751805790e+00 +6.7390316557639462e-01 +-2.4277578491757503e+00 +-1.2153646141230796e+00 +6.9561479653343261e-01 +-2.5594791016025167e+00 +-7.7998456084093071e-01 +6.9252332346175716e-01 +-2.5759576315488038e+00 +-8.8496643956148136e-01 +7.1899591210236657e-01 +-2.4991050707117237e+00 +-1.2190932929427409e+00 +7.3604642808460008e-01 +-2.3932389497921873e+00 +-1.1564700241703199e+00 +8.9070736182191901e-01 +-2.4436310010569020e+00 +4.9416381043254143e-01 +1.0033789931849028e-01 +-2.6747058018559091e+00 +1.9032058909233942e+00 +4.6365643626644615e-01 +-4.8021132389070464e+00 +1.2372288036226560e+00 +1.1770874678721764e-01 +-3.5265822196397414e+00 +1.2354056092130556e+00 +1.3956609035272757e-01 +-3.5048993465028575e+00 +3.7479269791148262e-01 +3.5947817924117775e-01 +-2.6576378398283671e+00 +1.2779018469535273e+00 +3.6665910513340561e-01 +-3.6949536675980155e+00 +4.0501182000061992e-01 +7.2053119019205025e-02 +-2.6289081274396455e+00 +1.3365118324853902e+00 +-3.2575085059226523e-02 +-2.4250765747687906e+00 +1.2768327364207246e+00 +5.1124257882783852e-02 +-3.5549050772355244e+00 +1.3425616175106421e+00 +1.5519945426272108e-01 +-2.4322079147778273e+00 +4.1366688562811599e-01 +4.1614896753338176e-01 +-2.6675610776256424e+00 +1.3407981519241920e+00 +-5.5584460323563123e-02 +-2.3686908073813506e+00 +4.2633659142592473e-01 +1.0192563922099637e-01 +-2.6555288707231468e+00 +1.2429805659752562e+00 +1.4026572011934609e-02 +-3.5187410063268376e+00 +1.3072647049995043e+00 +1.1414617192681467e-01 +-3.5990407924180090e+00 +1.3072647049995043e+00 +1.1414617192681467e-01 +-3.5990407924180090e+00 +-1.1345940541300199e+00 +5.1265083953056900e-01 +-2.3877303203699123e+00 +1.1480393125113959e+00 +2.6876068225824296e-01 +-3.3935362949861196e+00 +-1.3584150138162800e+00 +6.2798420358753770e-01 +-2.4023997059022024e+00 +1.8382087615348965e+00 +4.5706156260925535e-01 +-4.6914767613259070e+00 +4.1071611129851893e-01 +4.4108859480857382e-01 +-2.6518986811018164e+00 +4.0273023395056384e-01 +4.5173159816001685e-01 +-2.6689114875394964e+00 +-1.1372945275412198e+00 +2.5492126562471024e-01 +-2.3822753120247362e+00 +-1.1313766496125128e+00 +3.8116496983323878e-01 +-2.3799842654856951e+00 +1.3231095303261393e+00 +5.0368870241912861e-02 +-3.6444601649029784e+00 +1.3176373181051728e+00 +1.0327485912044498e-01 +-3.6325868229399574e+00 +1.3176373181051728e+00 +1.0327485912044498e-01 +-3.6325868229399574e+00 +1.6888777233243553e+00 +1.4780837812004102e-01 +-4.1504833346564984e+00 +1.0835675924537536e+00 +2.7394260283785449e-01 +-3.2805186199886931e+00 +1.3123256515044830e+00 +1.7940265933298841e-02 +-3.6179145965702837e+00 +-1.3210947196871152e+00 +4.6445761824134152e-01 +-2.3959984418474698e+00 +-1.1333083821522985e+00 +4.4982583691615824e-01 +-2.3852192903342506e+00 +1.3618893101870524e+00 +1.2843851790871511e-01 +-3.6761352987168237e+00 +-1.1393130244300245e+00 +4.6765768896275123e-01 +-2.3896884061453223e+00 +1.3599952503919943e+00 +8.9119562752241518e-02 +-2.3232648005517462e+00 +2.9743153380572278e+00 +3.6128966678697438e-01 +-6.9156144417193808e+00 +1.0699731999882947e+00 +2.8275010322760702e-01 +-3.2723068830855446e+00 +-1.4168496769823786e+00 +6.3678956259383457e-01 +-2.3990697214523622e+00 +3.0007183568671745e+00 +4.3489087277279465e-01 +-6.8861356329481884e+00 +1.0430200214133007e+00 +3.8874605087229586e-01 +-3.3455037754961743e+00 +1.8456932597934588e+00 +4.3536532217466994e-01 +-4.6197045705595574e+00 +-1.1653879164602552e+00 +6.6758706450656691e-01 +-2.3981866408622783e+00 +-1.3120209177801043e+00 +7.3493743463472816e-01 +-2.4153761062940560e+00 +-1.3029859899209173e+00 +7.3514635144587026e-01 +-2.4166937319680080e+00 +-1.2660264697373380e+00 +7.7923424318773871e-01 +-2.6397728460705681e+00 +-1.1731925365974758e+00 +7.5244573917476287e-01 +-2.3978718736053364e+00 +1.5821380946355490e+00 +-5.5808411364560835e-02 +-3.9656147702232176e+00 +1.3495078045380338e+00 +2.0985709771115378e-02 +-3.6496253520441013e+00 +-1.0116564054509942e+00 +4.3229870023832534e-01 +-2.4224037066485531e+00 +1.6002698598051057e+00 +1.6793616269463565e-01 +-4.0315309155434909e+00 +1.3395532816735549e+00 +1.0315903228357488e-01 +-2.4292450822376184e+00 +1.3395505637907590e+00 +1.2607225682500148e-01 +-2.4287044294661633e+00 +1.0443489230154712e+00 +3.7618163098590363e-01 +-3.3474315176829066e+00 +-9.6944927279633697e-01 +6.5018562050514106e-01 +-2.4520576240114140e+00 +1.6500348046467241e+00 +-7.6547279051664405e-02 +-4.0435366132584525e+00 +1.3279607162669942e+00 +-3.5921238197401763e-02 +-2.3691675524981100e+00 +1.2653988542369674e+00 +2.3221734040036315e-02 +-3.5283383963408927e+00 +1.3785699470999588e+00 +-3.4083331658838027e-02 +-2.2822465418757933e+00 +2.5218581827005768e+00 +4.0641145295048663e-02 +-5.7038419646781584e+00 +1.6688032221669222e+00 +7.7459469886486249e-02 +-4.0725092192561894e+00 +1.6532779127099539e+00 +7.8418189968295124e-02 +-4.0518999085729028e+00 +1.2297880166519497e+00 +1.8100776904007868e-01 +-3.4968775636507798e+00 +1.8525212474674602e+00 +2.1029580858742281e-01 +-4.4928785658894190e+00 +1.2713786182820384e+00 +2.8115816141549599e-01 +-3.5979558432403080e+00 +2.6101192051354269e+00 +4.2390222521335263e-01 +-6.0827924063903120e+00 +3.0214473426155597e+00 +4.8707285576197940e-01 +-6.9452209910504106e+00 +-1.1114492887287484e+00 +6.3495976885533567e-01 +-2.3760039784004281e+00 +1.8309561787558843e+00 +4.3669201491588056e-01 +-4.6194792388255062e+00 +-1.3077733817894548e+00 +7.3505119912137373e-01 +-2.4164451352220819e+00 +4.8526814903379972e-01 +4.4677392459628246e-01 +-2.6782498639541998e+00 +-1.2722662455711655e+00 +7.3582771440793582e-01 +-2.4054801362145848e+00 +7.7189329136077669e+00 +1.5929679191164015e-01 +-1.3436466528814709e+01 +4.5154470035830716e+00 +-2.4046263712461347e-01 +-8.5825206552699616e+00 +1.8222606802249657e+00 +5.5596013970816460e-01 +-3.0872988868159648e+00 +4.5669504995229753e+00 +-3.0110416945590690e-01 +-8.5759108786891751e+00 +4.5980543546247468e+00 +-1.0711205855621789e-01 +-8.6382979049220268e+00 +2.9629867357849315e+00 +5.5658984230994601e-01 +-6.6443729922344250e+00 +4.9042530178684496e+00 +-1.4017417420942321e-01 +-8.9950383839189776e+00 +-1.5805420549507954e-01 +4.5542133857515721e-01 +-3.6880288970615394e+00 +2.1460058663307615e+00 +4.4551605752215201e-01 +-2.7482004724843314e+00 +2.5500453892576325e-02 +4.7230710773499213e-01 +-3.0372978788747647e+00 +1.7540379103816202e+00 +1.3704282846049623e-01 +-2.1750348804875799e+00 +1.7475022277820362e+00 +1.3631131723697970e-01 +-2.1680442250410996e+00 +1.5016276581881212e+00 +1.2783289598374605e-02 +-2.2075201453750619e+00 +1.4166394194051593e+00 +5.7889101489984753e-02 +-2.2725114849613295e+00 +1.5400807528044436e+00 +1.2319252819821651e-01 +-2.2570640890329230e+00 +1.5400807528044436e+00 +1.2319252819821651e-01 +-2.2570640890329230e+00 +1.6273469006636272e+00 +1.3139892729663233e-01 +-2.1709277403249323e+00 +1.6273469006636272e+00 +1.3139892729663233e-01 +-2.1709277403249323e+00 +1.5669972110097572e+00 +1.3527784211003552e-01 +-2.2181788936763724e+00 +1.4759371581409881e+00 +2.3074318209483563e-01 +-2.2575321745795454e+00 +2.0521796450052827e+00 +3.2253776791136418e-01 +-2.4795191621590118e+00 +2.0521796450052827e+00 +3.2253776791136418e-01 +-2.4795191621590118e+00 +-2.4353284199565201e-01 +4.1867228203917500e-01 +-3.6565894447477665e+00 +1.2548387986254061e-01 +5.1387398777573878e-01 +-3.0005881137341706e+00 +-8.6965596223353731e-02 +5.6001773133148913e-01 +-3.5233873243318561e+00 +1.4047718989463889e+00 +8.7415972829843844e-03 +-2.2579793478832229e+00 +1.5950100757384218e+00 +4.4325147452300442e-02 +-2.1915713401764108e+00 +5.8398149932914190e-01 +1.3091373137389037e-01 +-2.7421725817900349e+00 +1.4135436728820172e+00 +1.8974806046727971e-01 +-2.2021787886435651e+00 +-6.7518302995727891e-02 +3.0039757782810811e-01 +-3.3389996333083136e+00 +-1.4327502770490794e-01 +3.4549747395587244e-01 +-3.4699510251203529e+00 +-6.0754147460019080e-02 +4.7548058332472015e-01 +-3.5155360458007663e+00 +-1.0768277603144241e-01 +4.8649581759276861e-01 +-3.5192520652308907e+00 +1.5859320498874070e+00 +1.1600738054050809e-03 +-2.1837938625187956e+00 +1.5847017449430110e+00 +1.2403524228609094e-03 +-2.1822199599047361e+00 +1.9936223339071752e+00 +-3.6379947591637903e-03 +-2.3607894718185878e+00 +1.6555190187953126e+00 +5.7205171026426666e-02 +-2.1406337128802870e+00 +1.5980005931599364e+00 +1.1439809965197496e-01 +-2.1977465339755682e+00 +1.4105495656186759e+00 +1.1862298527471050e-01 +-2.2673729919677292e+00 +1.6408639933179632e+00 +1.1857662714775075e-01 +-2.1266481923297320e+00 +1.6408639933179632e+00 +1.1857662714775075e-01 +-2.1266481923297320e+00 +1.6738373982881509e+00 +1.4632424852546189e-01 +-2.1616411835166063e+00 +1.6738373982881509e+00 +1.4632424852546189e-01 +-2.1616411835166063e+00 +1.5954152786222027e+00 +1.4731996408416498e-01 +-2.1943541532690971e+00 +1.4283172669422244e+00 +1.4644447381042128e-01 +-2.1840506275915357e+00 +1.6453903232571154e+00 +1.8464611628463798e-01 +-2.1694139192354860e+00 +1.4621246412423241e+00 +1.8288448505105084e-01 +-2.1927959200132761e+00 +1.6744542297469807e+00 +1.8465184514394559e-01 +-2.1115693332512788e+00 +5.3960381284648751e-01 +1.9993125709127330e-01 +-2.7051982961664445e+00 +1.6935077915889385e+00 +2.1685435090126509e-01 +-2.1063515433022042e+00 +1.6219240244252446e+00 +2.1790227126978909e-01 +-2.1694762676753605e+00 +1.5653993450204065e+00 +2.1600675366763217e-01 +-2.2171848922561908e+00 +-1.6560583122277381e-01 +2.5889398198703800e-01 +-3.4878091939997340e+00 +-2.6839523145082095e-01 +2.8074710534129621e-01 +-3.7400370424514953e+00 +1.4428518403819512e+00 +2.4283685482543876e-01 +-2.2061475170217535e+00 +1.7944124262155425e+00 +2.4896057237733973e-01 +-2.2404773347497535e+00 +-1.0991142314741097e-01 +2.9666754191099404e-01 +-3.4532045046500279e+00 +-1.8562313971014471e-01 +3.0302156514651074e-01 +-3.5662718085740210e+00 +-2.0049141709728751e-02 +3.0106293008983681e-01 +-3.2174086662293897e+00 +-9.7759508861452113e-02 +3.1867950652516175e-01 +-3.3701831040285430e+00 +-1.3148095627646886e-01 +2.1839965533282094e-01 +-7.1261820625736694e-01 +-2.6770531708568773e-01 +3.7224127598745632e-01 +-3.7358344108440882e+00 +-1.6151686128487253e-01 +3.8143966412863650e-01 +-3.4909742316407537e+00 +2.0647824948696627e+00 +4.4498546324136823e-01 +-2.7725095049318398e+00 +2.0647824948696627e+00 +4.4498546324136823e-01 +-2.7725095049318398e+00 +1.9851792702977893e+00 +4.5313131386814220e-01 +-2.9246380197154456e+00 +1.9766955518741038e+00 +4.7941307661890037e-01 +-2.8765451639490007e+00 +1.9766955518741038e+00 +4.7941307661890037e-01 +-2.8765451639490007e+00 +1.7772989005105053e-01 +4.9136574191289178e-01 +-3.0648969843055758e+00 +-3.5908411329704806e-02 +5.3233101502867164e-01 +-3.5490713857431135e+00 +-1.3200881254026725e-01 +5.5164214717433702e-01 +-3.5369399884758894e+00 +5.9607089044437601e-02 +5.6677925979461408e-01 +-3.1383627719562113e+00 +9.8640406867361946e-02 +5.6508901832018654e-01 +-3.0649707700677493e+00 +9.8640406867361946e-02 +5.6508901832018654e-01 +-3.0649707700677493e+00 +2.2362085797541040e-01 +5.8386058155097931e-01 +-3.0813734367544692e+00 +9.0290113163174840e-02 +5.9148140365069901e-01 +-3.1312554599545579e+00 +-4.1984006219050390e-01 +1.0869797552566894e-02 +-6.5535713330789525e-01 +1.5511911894246506e+00 +-2.7612492617604917e-02 +-2.1733018417282421e+00 +1.4581596871817215e+00 +-2.5143401620173918e-02 +-2.2049658940738568e+00 +-1.3381341390297513e-01 +9.6352371937912670e-02 +-7.0677582785967230e-01 +4.6668748583256370e-01 +1.1369371167218834e-01 +-2.6768339767722593e+00 +2.0144061188908662e+00 +1.0443392910762714e-01 +-2.3824391214715632e+00 +1.5866331114532850e+00 +1.1484714431262889e-01 +-2.1860294949744388e+00 +1.3998675970477072e+00 +1.3080487087376041e-01 +-2.2125082960288229e+00 +1.9893053817667565e+00 +1.3372464363799902e-01 +-2.3584259955906459e+00 +1.3833018068885123e+00 +1.3813025753920352e-01 +-2.2676012839514481e+00 +1.5465910426252025e+00 +1.8571087547363860e-01 +-2.2200532263232313e+00 +4.9644838332023639e-01 +2.3221351423692063e-01 +-2.6764377032072164e+00 +1.5586052947791884e+00 +2.3388821305555818e-01 +-2.2444021373526462e+00 +3.2710537878687440e-01 +2.4708273472897976e-01 +-2.6536747244064980e+00 +8.6199995383777295e-01 +2.4189708968552767e-01 +-1.6641799531015873e+00 +1.4188787867140280e+00 +2.7199673677152114e-01 +-2.2061474935202252e+00 +1.4222142335221246e+00 +2.7168087438478011e-01 +-2.2102418808792694e+00 +1.4334278022981151e+00 +2.9311208119004195e-01 +-2.1940799184158863e+00 +1.4428929349839978e+00 +2.9377692786151943e-01 +-2.2067222693205695e+00 +2.0513378581087114e+00 +3.1954818458036888e-01 +-2.5346154127848739e+00 +1.0577832336583640e-02 +3.6820412458213991e-01 +-3.1203921040290798e+00 +-1.2375895890877563e-01 +3.8514974372339600e-01 +-3.4332698179771728e+00 +-1.3040381189018822e-02 +3.9280107194661124e-01 +-3.2255991247222076e+00 +-2.7817995123610351e-01 +4.2279219610104696e-01 +-3.7429254983168212e+00 +-6.1522229885031976e-02 +4.0584331934369849e-01 +-3.3744558584548927e+00 +-2.3720348251122719e-01 +4.2945505131126477e-01 +-3.7814182364557869e+00 +-3.4093788424970395e-01 +4.4528548612261332e-01 +-3.8986596138428182e+00 +-1.8062504561948554e-02 +4.0963927024668828e-01 +-3.2087546653632359e+00 +-8.3414378786068399e-01 +3.8322220453051653e-01 +-2.5983018116583270e+00 +1.9850838312837547e+00 +4.4614542029464338e-01 +-2.8748223185098167e+00 +-6.3855243106974158e-03 +5.3195156652105646e-01 +-3.5168208637957812e+00 +4.2866119925315194e-02 +5.4265200627968790e-01 +-3.6058806791711815e+00 +6.8143501318547406e-02 +5.1624835875023889e-01 +-3.0863376852022117e+00 +-4.4037530544622172e-02 +6.2488896329275168e-01 +-3.7453321785081535e+00 +1.0613904035335245e-01 +5.6913200438225564e-01 +-3.1038908992181362e+00 +1.2676139900015293e-01 +5.9809970734894169e-01 +-3.0154471729183761e+00 +1.4390336942758506e+00 +-5.1975015061682381e-02 +-2.0899657585820512e+00 +3.7584240506081623e-01 +2.4675288766368098e-02 +-2.6496747075089835e+00 +1.4025532167994255e+00 +7.6402805597322709e-02 +-2.2542874159663806e+00 +1.4443762658876618e+00 +8.1009862016021811e-02 +-2.1993744640146931e+00 +1.6500552390766603e+00 +8.0843532604876311e-02 +-2.1511306422227179e+00 +1.4479511370666605e+00 +1.1367477338391489e-01 +-2.2012379750291200e+00 +1.9996513626500321e+00 +1.1724510278477412e-01 +-2.3395206021608796e+00 +1.9880741031070968e+00 +1.4416833040064631e-01 +-2.3264114027555767e+00 +1.9960749830000890e+00 +1.4399862092691249e-01 +-2.3352040117223503e+00 +1.6756673993292801e+00 +1.4461118477327781e-01 +-2.1294328585812505e+00 +1.9986411398735977e+00 +1.6091868110496535e-01 +-2.3201305743920080e+00 +2.0044878367124710e+00 +1.6064026130629580e-01 +-2.3264143298537787e+00 +1.5035813657575725e+00 +2.0446018523852669e-01 +-2.2315280820462191e+00 +1.5884432231736481e+00 +2.0587379800343347e-01 +-2.1883710218831220e+00 +1.5884432231736481e+00 +2.0587379800343347e-01 +-2.1883710218831220e+00 +-2.1052624601549669e-01 +2.8199491715912495e-01 +-3.6484453311439702e+00 +1.5722358228936650e+00 +2.4076039221206705e-01 +-2.2116188997123807e+00 +1.3911271287832681e+00 +2.7158765807113161e-01 +-2.2459034535519669e+00 +-7.8712330943372922e-04 +3.0588823798401865e-01 +-3.1806212174813959e+00 +-7.8712330943372922e-04 +3.0588823798401865e-01 +-3.1806212174813959e+00 +-2.5061565303876931e-01 +3.4577627658516996e-01 +-3.7199258738336707e+00 +-2.1400091152728526e-01 +3.5145153459443768e-01 +-3.6253440532506094e+00 +-3.5524140144190118e-03 +3.3490493548392219e-01 +-3.1770177959687671e+00 +-1.5209085032938847e-03 +3.3530463651447839e-01 +-3.1848041718325968e+00 +-1.4401406845292519e-01 +3.5601925895549186e-01 +-3.4513535887586499e+00 +-1.9359670099566967e-01 +3.6869953898310964e-01 +-3.6053312420305046e+00 +1.0889369402032705e-02 +3.9037430291042979e-01 +-3.1515447234897320e+00 +3.9331377972134174e-01 +3.7187802361571420e-01 +-2.6653491207449100e+00 +-1.6335018303918059e-01 +2.4791691838495775e-01 +-7.0219858313607619e-01 +1.9115055724628585e+00 +4.4232469260358698e-01 +-2.9655228190183536e+00 +1.9115055724628585e+00 +4.4232469260358698e-01 +-2.9655228190183536e+00 +2.0155357953652153e-01 +4.0644181967764936e-01 +-2.7555859324196166e+00 +2.0155357953652153e-01 +4.0644181967764936e-01 +-2.7555859324196166e+00 +-3.0535120592476001e-01 +4.8121066388135980e-01 +-3.8330674982265274e+00 +1.9108585423617113e+00 +4.6269943397157043e-01 +-2.9655523715275360e+00 +-7.9640686077883438e-02 +4.8726375569792879e-01 +-3.5542648788055913e+00 +2.0790456346026400e+00 +4.7074284053544946e-01 +-2.7454053393739493e+00 +8.0477217244772400e-02 +5.4079287129179265e-01 +-3.5726832709061287e+00 +-1.6826195039879507e-01 +5.4717690532964092e-01 +-3.6951085832877912e+00 +8.4363929278324923e-02 +5.4417393813072412e-01 +-3.0843536368015791e+00 +1.0883622181523668e-01 +5.5159996287795710e-01 +-2.9864456958087362e+00 +-2.1553038057067775e-01 +7.0973985536182693e-01 +-3.8036909726533956e+00 +-1.5535872971398854e-01 +7.1335946265236005e-01 +-3.8367833320626725e+00 +1.4728274913939794e+00 +-7.3383438862277148e-02 +-2.2035344992842938e+00 +1.4038583500905897e+00 +-3.4610469584595287e-02 +-2.0681537885709234e+00 +3.8501040661941566e-01 +-1.9292337534800207e-02 +-2.6438815425568025e+00 +1.9978105945632336e+00 +-2.1090039254256402e-02 +-2.3316019453031092e+00 +2.0001425422402073e+00 +7.8887018201370986e-03 +-2.3368046814634238e+00 +1.5975988691549321e+00 +1.8832437457586563e-02 +-2.1984180897936509e+00 +2.0030460494087028e+00 +3.4445744395558600e-02 +-2.3406356592544908e+00 +1.5936772861625097e+00 +4.7600167866497116e-02 +-2.2085613943134241e+00 +-1.4429576097527089e-01 +9.3322045146276636e-02 +-7.1567388062415294e-01 +1.6600472686583045e+00 +8.1535507229004711e-02 +-2.1078366346527484e+00 +1.5959673159090519e+00 +8.2193677985337832e-02 +-2.1478355895535164e+00 +1.4207028417499621e+00 +8.3513233550962435e-02 +-2.2533381251766951e+00 +-7.6099642224520758e-02 +1.0731207286699534e-01 +-6.6025823777809400e-01 +1.3685976840020897e+00 +1.5492636386786796e-01 +-2.2710003663296190e+00 +3.3440692128771426e-01 +1.7387019833847567e-01 +-2.6605117209638882e+00 +1.9790407162650754e+00 +1.8910623325960277e-01 +-2.3170018126040435e+00 +1.9893703649949515e+00 +1.8885156410776238e-01 +-2.3282568281603782e+00 +1.5368185312453870e+00 +2.0348243847458450e-01 +-2.2202345863369071e+00 +1.4994752059712102e+00 +2.3349350804985816e-01 +-2.2093639414202517e+00 +7.7630715350316926e-01 +2.6198239734033402e-01 +-2.9275450182726726e+00 +-2.2653244456461183e-01 +2.8960772735073270e-01 +-3.6750664493008403e+00 +1.4831497216075182e+00 +2.4343947766577401e-01 +-2.2253945145129808e+00 +6.7369346192743784e-01 +2.8678642671368043e-01 +-2.8303333442158096e+00 +-2.2985084031557126e-01 +3.1837611020121304e-01 +-3.6700450730395251e+00 +-2.6714009286956591e-01 +3.2786944421381775e-01 +-3.7200062068424562e+00 +-1.3967724103392573e-01 +3.2407198495189071e-01 +-3.4614424099922090e+00 +4.6521071354522098e-01 +3.2312368707808953e-01 +-2.6666329572065592e+00 +1.9130333429622810e+00 +3.7687271668422073e-01 +-2.9386457392366445e+00 +-1.4245286668852655e-01 +2.4273383276100352e-01 +-7.0618403373060923e-01 +-1.4903664904606664e-01 +2.4267565897461263e-01 +-7.1184874838346446e-01 +-3.6247823135799667e-01 +5.1461035555965806e-01 +-3.9612823665001735e+00 +-3.3323577151155592e-01 +5.1556307851971217e-01 +-3.8885125126967335e+00 +-2.8649115963187083e-01 +5.1918233458928320e-01 +-3.8159324973831610e+00 +-1.1239613071851239e-01 +5.0195513405376346e-01 +-3.5354398188145399e+00 +-1.1912948707673163e-01 +4.9843809419770541e-01 +-3.5054241964119002e+00 +5.8010300254171324e-02 +5.3005545124069398e-01 +-3.5668554924315110e+00 +5.6678213552505262e-02 +5.2912715715385861e-01 +-3.5623055533074242e+00 +1.9744631267072471e-01 +5.1345984464485284e-01 +-3.0444688237766329e+00 +2.8000279311323995e-01 +5.4211327048798441e-01 +-3.0742848749817360e+00 +-2.3822457385750614e-02 +3.4231385502168304e-01 +-7.5196962790882516e-01 +-1.8249438286594102e-01 +7.0180247626832015e-01 +-3.8119048169921443e+00 +-4.4023223894535990e-01 +4.1867339775225637e-02 +-6.6430791009809553e-01 +4.2102565848068357e-01 +-4.2194487496815390e-02 +-2.6551892251534430e+00 +6.7352969058373036e-01 +-5.1855992581845818e-02 +-2.8237870351795973e+00 +-1.5132448576687282e-01 +5.8921716924769253e-02 +-7.0013625831974791e-01 +2.0271416560904094e+00 +-2.9195341030496057e-02 +-2.3460648237100306e+00 +1.4305305651212059e+00 +-9.4568999888856916e-03 +-2.2011651410865083e+00 +3.7686624925157064e-01 +3.3938397000553441e-02 +-2.6596674528244786e+00 +1.5941781693361963e+00 +2.8333763420906929e-02 +-2.2106174353983028e+00 +-1.4501302880236666e-01 +8.2434818501824825e-02 +-7.1594913660971482e-01 +-1.4501302880236666e-01 +8.2434818501824825e-02 +-7.1594913660971482e-01 +-1.1849979295253293e-01 +8.9138520870557209e-02 +-7.0173087433077386e-01 +1.6283352545843104e+00 +6.8679725440238176e-02 +-2.1399314554677402e+00 +1.6625677847236382e+00 +6.9284096863134553e-02 +-2.1167953248199960e+00 +1.5719077687735952e+00 +7.1268075656260491e-02 +-2.1947014459534500e+00 +-1.2510098147442986e-01 +1.0932508572973830e-01 +-7.1243236589716863e-01 +1.9961269102595509e+00 +8.9104631404371942e-02 +-2.3316214947318112e+00 +1.4099157498594810e+00 +1.0927103400814751e-01 +-2.2534064329858703e+00 +8.6300160073892296e-01 +1.6574551615218977e-01 +-3.0210015712548683e+00 +1.6697530202870026e+00 +1.7124505850281180e-01 +-2.1160827232770405e+00 +1.6762916607856935e+00 +1.8168990628827950e-01 +-2.1128134430889522e+00 +1.4187818423162308e+00 +2.0670109083361612e-01 +-2.2178920226266747e+00 +1.4807788013139394e+00 +2.1612242071269774e-01 +-2.2202000108016668e+00 +1.6564862219331871e+00 +2.3529316772688413e-01 +-2.1538626896625712e+00 +1.5893458267818437e+00 +2.3622754493092513e-01 +-2.2014888781468942e+00 +-1.3124031646607578e-01 +3.2079725271811871e-01 +-3.4352764651412557e+00 +-7.5739197459249022e-02 +3.2732211331975708e-01 +-3.3348939893473504e+00 +-2.3749035035207813e-01 +3.6349422147003685e-01 +-3.6843902215596467e+00 +-1.4275871067093504e-01 +2.1721471036341064e-01 +-7.1956435413736464e-01 +-1.4275871067093504e-01 +2.1721471036341064e-01 +-7.1956435413736464e-01 +-2.2809548398451443e-01 +3.7567118768568608e-01 +-3.6728758874543179e+00 +-2.2796201118080597e-01 +3.7633138492732354e-01 +-3.6736980740702139e+00 +-1.9364251494412246e-01 +3.8690126229890409e-01 +-3.5858699669978158e+00 +-1.3721980005871057e-01 +3.8632315512441689e-01 +-3.4681300807770339e+00 +-6.3449628459575511e-02 +3.8621974723987934e-01 +-3.3459497052231901e+00 +-1.0747724329328891e-01 +3.9118813029025445e-01 +-3.4121606133679050e+00 +-1.0425405310953222e-01 +3.9392701016323289e-01 +-3.4257029686218874e+00 +-2.3309463868420693e-01 +4.0297144868642143e-01 +-3.6570567433968377e+00 +-3.1885612618571403e-02 +3.9745484987484220e-01 +-3.2437430225154458e+00 +-1.3940047756664978e-01 +4.1009467290264617e-01 +-3.4617300198893415e+00 +-1.8736490739171821e-01 +4.1568298083283012e-01 +-3.5594040719001785e+00 +-9.3182283828113610e-02 +4.2159432984696710e-01 +-3.3765088716249783e+00 +-8.2863562517495923e-02 +4.2555417228066755e-01 +-3.3585065476200375e+00 +2.1045196267368507e+00 +4.2237753688770541e-01 +-2.7964405913747439e+00 +-5.4736397121608422e-03 +4.2220262177212597e-01 +-3.1783914322846893e+00 +-5.4736397121608422e-03 +4.2220262177212597e-01 +-3.1783914322846893e+00 +1.9116338838343558e-01 +4.0257912416696973e-01 +-2.7772582061887059e+00 +2.0888707755237230e+00 +4.6836408162216170e-01 +-2.7859884355076217e+00 +-7.8617404004448110e-01 +4.2175404341673323e-01 +-2.6498479951927965e+00 +-2.5863337925592124e-02 +5.0502504085545630e-01 +-3.5630447676686150e+00 +2.0095491050672654e+00 +4.9098641701763662e-01 +-2.8559407853473018e+00 +2.0095491050672654e+00 +4.9098641701763662e-01 +-2.8559407853473018e+00 +4.7653134523798329e-01 +4.5154084842294145e-01 +-2.6816554745296686e+00 +-1.0762973685394281e-01 +2.9850059547010649e-01 +-7.0538496836178421e-01 +-1.5287529753766871e-01 +5.9929080382261324e-01 +-3.7368913482329194e+00 +7.9491452973191823e-02 +5.6851322582442343e-01 +-3.1381013081182445e+00 +2.1413678774226583e-01 +5.7466525281095282e-01 +-3.1001473126395758e+00 +1.2242144803497243e-01 +5.7197632768101370e-01 +-3.0423591611405771e+00 +1.5637488407077910e-01 +5.8383683043535772e-01 +-3.0526090537924770e+00 +-3.1612031145937416e-03 +6.6257931322741948e-01 +-3.8209419880983151e+00 +-5.0798097488008634e-02 +3.3596876472094667e-01 +-7.0269993392738173e-01 +-4.5311025219576015e-02 +-6.9197423698786238e-03 +-4.2106062520803694e-01 +1.9926854420847995e+00 +-8.9750845311774879e-02 +-2.3508568880028480e+00 +2.0149433276940667e+00 +-7.0442972435011617e-02 +-2.3321732424520438e+00 +2.0178901551068362e+00 +-6.0508506263750747e-02 +-2.3343541947583297e+00 +1.9952309305188087e+00 +-3.8770978509048537e-02 +-2.3253692691470085e+00 +1.9844342108481496e+00 +-3.8272071422472645e-02 +-2.3134242422374864e+00 +4.1074593475520710e-01 +-1.2049559441096513e-02 +-2.6568641837034743e+00 +4.1144199364840567e-01 +1.5494359344431819e-02 +-2.6578921354885203e+00 +4.1098284642265742e-01 +1.5631464032956826e-02 +-2.6567344191363826e+00 +1.4023406705399020e+00 +2.8112820212152299e-02 +-2.2631644345296480e+00 +3.5700007462081301e-01 +3.7578276053952565e-02 +-2.6389857279811899e+00 +-1.4274088845826347e-01 +8.9760236350372669e-02 +-7.1051923604104850e-01 +2.0087656508425842e+00 +3.8184370456857644e-02 +-2.3660686990334776e+00 +5.3685620656293920e-01 +5.6923871732065708e-02 +-2.7038322431467758e+00 +7.3477317133750197e-01 +6.0415479384515414e-02 +-2.8923656902530954e+00 +1.3706958785119341e+00 +6.8614128811599825e-02 +-2.2556821826461908e+00 +1.4338485951251381e+00 +9.4883887045358092e-02 +-2.2170679245874125e+00 +1.6167908014650481e+00 +9.3343259674525003e-02 +-2.1468774270257454e+00 +1.6598302430011338e+00 +1.0233807102393010e-01 +-2.1017324589907820e+00 +1.5229551655243430e+00 +1.0666485407717026e-01 +-2.2482269308143477e+00 +3.7731983286622711e-01 +1.2164832352266221e-01 +-2.6429479331579007e+00 +1.5992399937873822e+00 +1.3622847884204548e-01 +-2.1856879785099164e+00 +2.5080371781757033e-01 +1.6041956746747196e-01 +-2.6690341907413018e+00 +-1.2369966661410786e-01 +1.4295709484028604e-01 +-7.1321145867487790e-01 +-1.2081626354602416e-01 +1.4334826423449870e-01 +-7.0816703118753543e-01 +1.6834717026011154e+00 +1.6341735609015806e-01 +-2.1186385152909581e+00 +1.6288275222898165e+00 +1.8185597793179095e-01 +-2.1538067240335885e+00 +1.5421045311471464e+00 +1.9245987019841518e-01 +-2.2130250892721421e+00 +1.5741190538051606e+00 +2.0020057458236196e-01 +-2.2352850416674204e+00 +1.6970222509439350e+00 +2.0266364454274477e-01 +-2.0932966662023884e+00 +1.6038520708943300e+00 +2.2528357491470341e-01 +-2.1922834347140432e+00 +1.5218828143129730e+00 +2.2657340230138789e-01 +-2.2584990092440465e+00 +1.5416161607013781e+00 +2.2630841225350265e-01 +-2.2434994954277392e+00 +-7.8742354965481001e-02 +2.8611498792305345e-01 +-3.3367730416017394e+00 +1.5919931329196477e+00 +2.4849302343493579e-01 +-2.2260124551662517e+00 +1.6576461464427139e+00 +2.4887526188404335e-01 +-2.1740276370221654e+00 +-2.7198693762057818e-01 +3.1037186425112157e-01 +-3.7391981939588819e+00 +1.9892974743403700e+00 +2.9353343070584481e-01 +-2.4388636186048096e+00 +-9.2740047631891073e-02 +3.2757453943680204e-01 +-3.3836242268108672e+00 +-2.4850877157578763e-01 +3.6188068138177248e-01 +-3.7034916112412626e+00 +-1.7831425994056357e-01 +3.7919477909025534e-01 +-3.5848358877367605e+00 +-1.4472276342788018e-01 +3.7112393650013642e-01 +-3.4863859871601379e+00 +-9.2556616371567854e-02 +3.7650655322677412e-01 +-3.3820826768157830e+00 +1.9074973516325568e+00 +3.7974432242735295e-01 +-2.9502083839958697e+00 +-2.4232157620393924e-01 +4.0585172443422735e-01 +-3.6837504079690366e+00 +6.2511457363103329e-01 +3.6381803993195122e-01 +-2.7905154989119185e+00 +3.4599842060437569e-03 +3.8154170183828556e-01 +-3.1712931513324660e+00 +-9.5455004150735795e-02 +3.9644766901658574e-01 +-3.3715908594228221e+00 +-9.5455004150735795e-02 +3.9644766901658574e-01 +-3.3715908594228221e+00 +-8.5834290533965116e-02 +4.0196858376200506e-01 +-3.3660124136674647e+00 +-4.4256592034161574e-02 +4.0111188341803566e-01 +-3.2754168632883265e+00 +-5.1315095764632779e-02 +4.0276823949855961e-01 +-3.2953940066263119e+00 +-1.2822313342548958e-01 +4.1430934276025644e-01 +-3.4470561720704618e+00 +-7.5418701257487890e-03 +3.9977866698899694e-01 +-3.1689150204852661e+00 +-3.6261326685926659e-02 +4.0983484177330698e-01 +-3.2631921612045049e+00 +1.9102514038898211e+00 +4.1447459078537935e-01 +-2.9820996868029535e+00 +-1.8546557058407304e-01 +4.3749372092444216e-01 +-3.5689185135466945e+00 +-4.4581620634761975e-02 +4.2491849486487276e-01 +-3.2745241136950858e+00 +1.6515577860904229e-01 +4.0257041564088425e-01 +-2.8103348352666977e+00 +-1.5656380495397970e-01 +2.5530389795450703e-01 +-7.0043170334376692e-01 +1.9617289663335427e+00 +4.4329261985094115e-01 +-2.8719802574074604e+00 +5.0967224502346598e-01 +4.1434869542568015e-01 +-2.6970464468415849e+00 +2.0333487653040376e+00 +4.6055486616767205e-01 +-2.8504894972375681e+00 +1.9624600345004699e+00 +4.6448553700561362e-01 +-2.9187610718373387e+00 +1.9764447629926103e+00 +4.6336931697354677e-01 +-2.8920429146764666e+00 +1.9764447629926103e+00 +4.6336931697354677e-01 +-2.8920429146764666e+00 +1.9691694296504159e+00 +4.6446369364817802e-01 +-2.9046247061435451e+00 +2.7164752628421097e-02 +4.5035684168192830e-01 +-3.0871638535381818e+00 +-3.2724780031517681e-01 +5.1223940680354230e-01 +-3.8684254014989494e+00 +4.4932886291744405e-02 +4.5586316910123631e-01 +-3.0792808317507494e+00 +4.4932886291744405e-02 +4.5586316910123631e-01 +-3.0792808317507494e+00 +-3.1330628178977443e-01 +5.1365677734364334e-01 +-3.8498944438841818e+00 +-1.4687671415400688e-01 +5.0413334380133756e-01 +-3.5493670396129975e+00 +1.9960455763868603e+00 +4.8520435177880739e-01 +-2.8602553967254289e+00 +4.0325773548680394e-01 +4.5056610334511477e-01 +-2.6596420181569793e+00 +-1.0309487664787378e-01 +5.1818461334712118e-01 +-3.5415237621687710e+00 +-2.0865766830074092e-01 +5.4291833213228380e-01 +-3.7226128348168057e+00 +3.1937687569347978e-02 +5.4470197470066406e-01 +-3.5936724713671455e+00 +-1.5425905574667004e-01 +5.4449448520672239e-01 +-3.6110763843309135e+00 +-3.2710090589221580e-01 +5.7004741070667297e-01 +-3.8494881717264855e+00 +8.3590452309800126e-02 +5.1232816241399470e-01 +-3.0577670219823783e+00 +2.1469247008970682e-01 +5.2967707115391749e-01 +-3.0586230464854993e+00 +1.1619054364978046e-01 +5.3893728319511458e-01 +-3.0314201015476554e+00 +8.3643169600193468e-02 +5.5405922684856013e-01 +-3.0890537768118773e+00 +-1.0516213860662016e-01 +3.1924586658068504e-01 +-7.2203837201540133e-01 +1.5169645122848344e-01 +5.5855104689220381e-01 +-3.0513506754546422e+00 +1.5169645122848344e-01 +5.5855104689220381e-01 +-3.0513506754546422e+00 +-2.7000475294291327e-02 +6.5004900716648661e-01 +-3.7889325859485408e+00 +-3.8713250048605471e-02 +6.5683349203280150e-01 +-3.7889647183388693e+00 +-4.4440442981530381e-01 +-1.0264181988666365e-02 +-6.3948700994087515e-01 +4.3764702659077381e-01 +-8.0739971579232656e-02 +-2.6575558666854899e+00 +2.0187255011393974e+00 +-3.9986998868430448e-02 +-2.3216308520338513e+00 +1.4367063760541579e+00 +-7.7978167546396190e-03 +-2.2248323269941079e+00 +2.0071451344028723e+00 +1.6196995173954520e-02 +-2.3276395929949789e+00 +1.6380755002937224e+00 +6.1302527423386169e-02 +-2.1591555878481214e+00 +1.5948028796539222e+00 +7.1869447494308084e-02 +-2.1854025051737329e+00 +5.3480882231765392e-01 +7.9444773531623422e-02 +-2.6999536687712324e+00 +1.9958899476111944e+00 +9.2795447326249558e-02 +-2.3536896160501635e+00 +2.0096553837788202e+00 +1.0289103104923170e-01 +-2.3317540088033293e+00 +-1.0756392638675899e-01 +1.2571496207704158e-01 +-6.9160981271106570e-01 +-1.0202007218600176e-01 +1.3297339889578699e-01 +-6.8074605894652696e-01 +1.5862239793564579e+00 +1.3513009755349475e-01 +-2.2002491667611874e+00 +3.8405581168694081e-01 +1.6815206070957853e-01 +-2.6724442206059411e+00 +2.8168119203229941e-01 +1.6941676954724588e-01 +-2.6862935571854081e+00 +1.4171465281981337e+00 +1.9119232495816230e-01 +-2.2046636911072808e+00 +1.6004942354161500e+00 +1.9399342976864140e-01 +-2.1683494056335282e+00 +1.5988226446193829e+00 +1.9311473820578656e-01 +-2.1845027842543416e+00 +1.6711052772469559e+00 +1.9443814924696426e-01 +-2.1260587803236874e+00 +1.6242573053967948e+00 +1.9470820968125926e-01 +-2.1556455165631432e+00 +1.6864236614280601e+00 +1.9486721279524494e-01 +-2.0993960282007609e+00 +1.6837363185147352e+00 +1.9607992884030501e-01 +-2.1192782742968914e+00 +1.6075900501209150e+00 +2.0030888589582937e-01 +-2.1807903520964698e+00 +1.5728238479190004e+00 +2.0005034460923296e-01 +-2.2043318132582930e+00 +1.5729739310840627e+00 +2.0064068449173539e-01 +-2.2196020655406592e+00 +1.6824340889599620e+00 +2.0090444292058277e-01 +-2.0938232547515350e+00 +6.9675199939009091e-01 +2.3069965666598749e-01 +-2.8462239092854560e+00 +3.7446043630650155e-01 +2.2723149679006149e-01 +-2.6561279395109127e+00 +1.4120549554613200e+00 +2.2112677996508731e-01 +-2.2491844482611509e+00 +1.5842635600009956e+00 +2.3546648736150874e-01 +-2.2061691814158371e+00 +1.5842635600009956e+00 +2.3546648736150874e-01 +-2.2061691814158371e+00 +-1.6957508928013520e-01 +2.8049902098877683e-01 +-3.5091208224191046e+00 +-1.2958652835847401e-01 +2.8141374519658324e-01 +-3.4279965430642076e+00 +-1.7060650040065137e-01 +2.8745060964156988e-01 +-3.5372447638955635e+00 +-3.2936535698725511e-01 +3.0224676261757244e-01 +-3.8635292531698622e+00 +-3.1499651805526879e-01 +3.0255173639940691e-01 +-3.8374017576857855e+00 +-3.2303288556425813e-01 +3.0862899157234608e-01 +-3.8633038657666079e+00 +-3.6720164987254514e-02 +2.8888097747617336e-01 +-3.2075516973494729e+00 +1.6215018612692447e+00 +2.5753184619332609e-01 +-2.2107844667661634e+00 +6.8906397555916254e-01 +2.8098418916339474e-01 +-2.8434755396251461e+00 +-2.9835195019315627e-02 +3.0125519649630439e-01 +-3.2246157753538567e+00 +-3.5036124602249247e-01 +3.4631089338366505e-01 +-3.9011929456771268e+00 +1.6137804726880240e+00 +2.9783601298506268e-01 +-2.2390660311183890e+00 +1.6218531113324637e+00 +3.0238003829241616e-01 +-2.2591843813677404e+00 +-2.1761433124155322e-01 +3.5791700187154479e-01 +-3.6176271206523274e+00 +-1.7083068654530612e-01 +3.6208263789368045e-01 +-3.5236432729761860e+00 +-3.2795930154343428e-01 +3.8737949289874951e-01 +-3.8415236476114440e+00 +-2.8514571911742570e-01 +3.9097849182711314e-01 +-3.7602342413408580e+00 +-2.6393524615008429e-01 +4.0100834402336766e-01 +-3.7191665406035117e+00 +-8.5809810753333576e-02 +3.8973319813387991e-01 +-3.3681919664821933e+00 +-5.1738618859252426e-02 +3.8540835380611133e-01 +-3.2941085317293166e+00 +1.8952393348451044e+00 +3.8094326434022963e-01 +-2.8947115171717144e+00 +-1.3518240649158636e-01 +2.3577214770255150e-01 +-7.0263705232716511e-01 +4.2012744385913020e-01 +3.5498928969153531e-01 +-2.6463387874571827e+00 +-4.0871645458230237e-02 +3.8790815794464872e-01 +-3.2482459807070421e+00 +-3.7993902847016321e-02 +3.8866062368464549e-01 +-3.2599446361949935e+00 +-5.9263887349701033e-02 +3.9348024486103117e-01 +-3.2929401245117886e+00 +1.9023315991187810e+00 +4.0408587628228271e-01 +-2.9415710083837867e+00 +1.8978578265741959e+00 +4.1258604013780420e-01 +-2.9301205399285295e+00 +-1.1445991962905980e-01 +4.3178360987894654e-01 +-3.4121786254958586e+00 +-1.9604016544225569e-01 +4.5260233704428687e-01 +-3.7017905621322016e+00 +2.0078869414554372e+00 +4.3151400439625826e-01 +-2.8633321683835895e+00 +1.9673989249409691e+00 +4.3475300808722006e-01 +-2.9248362062868556e+00 +4.3815253038896695e-01 +3.9594991760842957e-01 +-2.6588627802781080e+00 +-1.6177781824257352e-02 +4.2843889989684941e-01 +-3.2046720029181603e+00 +1.9736009547902200e+00 +4.3427924576426480e-01 +-2.8883083391216493e+00 +-1.6737701540021574e-01 +4.4967395183353093e-01 +-3.5351120814781116e+00 +1.6010913287178483e-01 +4.0795949827501754e-01 +-2.8216805494862425e+00 +4.5622774617585299e-01 +4.0672104198296888e-01 +-2.6648880280959006e+00 +1.9686133869473748e+00 +4.4672382670311950e-01 +-2.9039620770989232e+00 +1.9596249387104876e+00 +4.4629077389830563e-01 +-2.9155806898613119e+00 +1.9802624453068043e-01 +4.1824398949315422e-01 +-2.7730359303493639e+00 +-1.5109434118572105e-02 +4.5749146289444276e-01 +-3.2105441071372964e+00 +-7.9308358766400799e-02 +4.8172972473584297e-01 +-3.5292598490975777e+00 +3.0806295056671967e-01 +4.2765934325990507e-01 +-2.6828862485220575e+00 +-2.9451374846092715e-01 +5.1347625105000239e-01 +-3.8049483012296088e+00 +-2.6011359952204033e-01 +5.0867720453724763e-01 +-3.7369482648344787e+00 +2.0096044240185944e+00 +4.7828777656996047e-01 +-2.8659817853234486e+00 +-7.3732467874301588e-01 +4.5016582337173550e-01 +-2.9881665841152651e+00 +2.0281321397919010e+00 +4.8237420503817102e-01 +-2.8762628436896529e+00 +-3.1077839440433663e-01 +5.2462516019190497e-01 +-3.8215362372636323e+00 +3.4943572220041408e-01 +4.4298429462370015e-01 +-2.6866864000729156e+00 +3.0061521694208174e-02 +4.7155281539173477e-01 +-3.0881026536934715e+00 +4.4922930130900089e-02 +4.7250128491028143e-01 +-3.0696610285639507e+00 +4.8902105989112335e-02 +4.7339737818560057e-01 +-3.0511084760834808e+00 +-3.4862555165911226e-02 +5.1417746098382189e-01 +-3.5255259870121285e+00 +-5.6549525814702351e-02 +5.1578444742646390e-01 +-3.5446823868637876e+00 +5.1609165647454283e-02 +5.2379261433138868e-01 +-3.5636648338289580e+00 +6.2103630495052367e-02 +5.2337054927853355e-01 +-3.5629914385502088e+00 +-1.3715116631360827e-01 +5.4494381976932760e-01 +-3.5869348983690594e+00 +1.5621906936694474e-01 +5.0437689867521363e-01 +-3.0199226536763608e+00 +-2.0180984780411587e-01 +5.6545759381892369e-01 +-3.7231946225085961e+00 +1.8571519786369342e-01 +5.1036083566992918e-01 +-3.0346519129137066e+00 +-7.6544384500973769e-02 +2.9809955902657131e-01 +-6.8352804245945575e-01 +2.0462647739409842e-01 +5.1595057194131966e-01 +-3.0319829953769339e+00 +-1.0743973517277006e-01 +5.6354333515327171e-01 +-3.5333414612384026e+00 +-2.7490611989638808e-01 +5.8855539497329468e-01 +-3.7861248359503965e+00 +2.8144519759716602e-01 +5.3984022584805624e-01 +-3.0910075195248452e+00 +2.0332890028898698e-01 +5.4025737888398417e-01 +-3.0570420916174945e+00 +1.3273554821444022e-01 +5.5100246103080974e-01 +-3.0383632851436495e+00 +2.8584710304072192e-01 +5.5739408430583759e-01 +-3.0468411625397143e+00 +-1.0318282257978996e-01 +3.2411766353645671e-01 +-7.1969894752546038e-01 +4.8908723368301758e-02 +6.4738351157000573e-01 +-3.8345062279213740e+00 +-2.2105375127100807e-01 +6.5967174528179018e-01 +-3.7771959125490890e+00 +-1.2783139732181142e-01 +6.6291525769109227e-01 +-3.7526179360012430e+00 +-4.1380839242403950e-01 +1.2039516966940165e-02 +-6.5304780728237022e-01 +-4.1380839242403950e-01 +1.2039516966940165e-02 +-6.5304780728237022e-01 +2.0156361466767065e+00 +-9.5973750721459805e-02 +-2.3186697208816898e+00 +1.6855057036170382e+00 +-7.4657541862327495e-02 +-2.1093229420446611e+00 +2.0177821668381890e+00 +-8.7017813645274292e-02 +-2.3221025420363142e+00 +1.4064133776678733e+00 +-5.6815901905991173e-02 +-2.0654702226033743e+00 +1.4652283198594547e+00 +-5.9083786303295020e-02 +-2.2014275996377419e+00 +1.9846618705547501e+00 +-7.3745778782325258e-02 +-2.3077711727862611e+00 +4.1837937977085904e-01 +-5.1587984826143601e-02 +-2.6549364890613592e+00 +4.1834829512050253e-01 +-4.5610453190530337e-02 +-2.6548249936190316e+00 +2.0209245368871835e+00 +-2.8284329553282497e-02 +-2.3269830959819280e+00 +-1.4689637100121752e-01 +7.2013879121009039e-02 +-7.1329604587953699e-01 +1.6961409530217777e+00 +5.2180112319102030e-02 +-2.1670682725263819e+00 +-1.4137028678525548e-01 +9.6254026826391226e-02 +-7.1401474863405867e-01 +-1.0887275033374195e-01 +9.6556647197019660e-02 +-6.8905625864694475e-01 +-1.0887275033374195e-01 +9.6556647197019660e-02 +-6.8905625864694475e-01 +2.0147353103461665e+00 +5.4144459615285967e-02 +-2.3351928125535415e+00 +6.5221123235819256e-01 +7.2384269603577092e-02 +-2.8039275667127086e+00 +2.0127498350681794e+00 +6.2369201094481908e-02 +-2.3349140676207178e+00 +7.4215970529199604e-01 +7.5567731255860165e-02 +-2.8916922271065912e+00 +-1.2239823942704649e-01 +1.0445219410135943e-01 +-6.9918126785846180e-01 +-1.2350998186594318e-01 +1.0791470245651615e-01 +-7.0605501129440362e-01 +4.4239086801160110e-01 +1.1361039244051648e-01 +-2.6659364413439817e+00 +1.9998291345162877e+00 +1.2235015597566348e-01 +-2.3572673650333846e+00 +-1.2986559442144813e-01 +1.5002916322418158e-01 +-7.1725500118999552e-01 +-7.9746586651394213e-01 +1.9212852735255850e-01 +-2.6320804620903506e+00 +4.0993032971228555e-01 +1.8584635164520230e-01 +-2.6593166821775527e+00 +3.7447750077737013e-01 +1.8703875304665993e-01 +-2.6584683586888480e+00 +1.6736926295429415e+00 +1.9595733441124238e-01 +-2.0949520103141785e+00 +-2.6461725350133491e-01 +2.5794556273982289e-01 +-3.7504891133397180e+00 +1.4481669193557045e+00 +2.1194417371603011e-01 +-2.1921925593574891e+00 +6.0646941455640602e-01 +2.4271932498019505e-01 +-2.7673432525199257e+00 +1.6109099143557501e+00 +2.2906715222781199e-01 +-2.1768132367063915e+00 +1.6325897255970350e+00 +2.3342543059508547e-01 +-2.1678791785946574e+00 +-8.5626209653106300e-02 +2.8251989300526825e-01 +-3.3658826735913512e+00 +1.6516629045810953e+00 +2.4425146207682588e-01 +-2.1591634080665534e+00 +-7.6006898245691831e-02 +2.8562283162654606e-01 +-3.3286387193914622e+00 +3.7562041080061437e-01 +2.6645190437554545e-01 +-2.6334585447280561e+00 +4.7691750205300382e-01 +2.7104034438034880e-01 +-2.6680842068853976e+00 +7.9852591942087381e-01 +2.9329401265166805e-01 +-2.9599054963719449e+00 +1.9857630582435393e+00 +2.8347330653056085e-01 +-2.4233416364987441e+00 +1.9904049699217525e+00 +2.8413695073718659e-01 +-2.4282546416907671e+00 +1.3736834380360401e+00 +2.7682033333973227e-01 +-2.2651740805093437e+00 +1.3511385743900848e+00 +2.7624555706839493e-01 +-2.2644646971080342e+00 +1.4005697358224238e+00 +2.7642159844792136e-01 +-2.2370605020878762e+00 +1.3962862572057415e+00 +2.7696077353020482e-01 +-2.2500504164508870e+00 +1.4244457894018103e+00 +2.7750426153099722e-01 +-2.2169746618159594e+00 +1.4073924095207946e+00 +2.7723238039087073e-01 +-2.2134076133485339e+00 +1.6124123725322788e+00 +2.9425422823579889e-01 +-2.2466507605792962e+00 +1.6342398993012519e+00 +2.9441990602848139e-01 +-2.2296713146203180e+00 +1.6406234115036684e+00 +3.0308227377832964e-01 +-2.2393932193721362e+00 +1.6414216591424318e+00 +3.0258848009408601e-01 +-2.2400885444421563e+00 +-2.2873572366986952e-01 +3.6236145776556555e-01 +-3.6446463625312933e+00 +-1.6681329288379754e-01 +3.7137969400353454e-01 +-3.5189554978659507e+00 +-9.2890899243225244e-02 +3.6826609355459128e-01 +-3.3581969558058309e+00 +-3.2718400372930972e-01 +4.3592278957929637e-01 +-3.8667981365657282e+00 +-3.1534621422483150e-01 +4.3675153698431213e-01 +-3.8461415460686474e+00 +8.5947236742591004e-01 +4.1493883939657494e-01 +-3.1780718250269833e+00 +2.0102627421752528e+00 +4.1430702768740901e-01 +-2.8674273076591796e+00 +4.6182986258055336e-01 +3.9386643827423667e-01 +-2.6630136979533741e+00 +1.9499397905618181e+00 +4.3156385742414105e-01 +-2.9145708110570854e+00 +2.1081425622179664e+00 +4.2981551838154231e-01 +-2.7958972932292667e+00 +2.0925273704896390e+00 +4.2937268701920545e-01 +-2.7998859590128231e+00 +-3.2893063601825218e-01 +4.7794385091094893e-01 +-3.8642932547182762e+00 +-2.3113162092948204e-02 +4.4034300128806148e-01 +-3.2130619499174871e+00 +3.4766009127736419e-02 +4.4313395355972618e-01 +-3.0893585703592148e+00 +5.8113530706729322e-01 +4.3472134738573842e-01 +-2.7370971180662744e+00 +1.7203933948713571e-01 +4.3632891929519974e-01 +-2.8111364627352486e+00 +2.0046581986574270e+00 +4.6977898011767427e-01 +-2.8468732952100959e+00 +-3.0287868215716957e-01 +5.1152058538821688e-01 +-3.8216303430600886e+00 +2.4718447197990293e-01 +4.3823003137256028e-01 +-2.7190581271449652e+00 +-7.0814396885065745e-02 +5.0801290254922815e-01 +-3.5358264996094357e+00 +-1.4810873586186646e-01 +5.1261321352505473e-01 +-3.5691140899627980e+00 +-3.3339852961105495e-03 +5.2412073562714179e-01 +-3.5916246929603788e+00 +2.0043110162328239e+00 +5.0693808017571407e-01 +-2.8755526971308956e+00 +-1.8464975901844607e-02 +5.6676008415077472e-01 +-3.6370781034682351e+00 +1.8523013957906395e-01 +5.1689016449792380e-01 +-3.0463266856883151e+00 +-1.0452684852233744e-01 +5.7388132357361599e-01 +-3.5510477510556666e+00 +1.4669888936377282e-01 +5.3727264043715028e-01 +-3.0474621165058053e+00 +-1.0532344713786183e-01 +3.1440518021260927e-01 +-7.2115877581844268e-01 +-9.4512926634861730e-02 +3.2085293716304475e-01 +-7.7261350073104518e-01 +-2.7973140768540672e-01 +6.4013328555475135e-01 +-3.9078439086583940e+00 +-2.8124059784458405e-01 +6.4638707109501148e-01 +-3.8915638582455516e+00 +-2.7131094851401227e-01 +6.4745149837059512e-01 +-3.8785077687231881e+00 +-2.7194310650752501e-01 +6.4699985290760842e-01 +-3.8739495624713034e+00 +-2.3547860544871399e-01 +6.5005261188425878e-01 +-3.7996937330906229e+00 +-6.2260501476599825e-02 +6.5620339919257309e-01 +-3.7887733596699813e+00 +-1.0132241828814672e+00 +2.0387736387460023e-01 +5.0705670492368793e-01 +-4.1387598438258555e-01 +-7.2130690056685411e-03 +-6.5258623087053280e-01 +1.4059845353186551e+00 +-5.5994989747405792e-02 +-2.0767099395561175e+00 +4.3666425357569399e-01 +-5.1621589268403344e-02 +-2.6567626007845226e+00 +2.0067683645055090e+00 +-6.4445697597202589e-02 +-2.3308607860321362e+00 +4.1252230193378620e-01 +-3.3340288827559079e-02 +-2.6535049234294652e+00 +5.9539138024677918e-01 +-3.9368687915509779e-02 +-2.7485407595627867e+00 +1.6040466955273300e+00 +1.0487565642733346e-02 +-2.1816703705208864e+00 +1.9698120129890311e+00 +4.0351347923863697e-02 +-2.3496207509823370e+00 +8.5529489869553355e-01 +5.2020481408681506e-02 +-3.0120201343855051e+00 +1.6129576170350597e+00 +6.3412980781035994e-02 +-2.1860058740135879e+00 +1.5674700462859312e+00 +6.3802490400781037e-02 +-2.1897048792440637e+00 +2.0076791288711089e+00 +5.8489180911817130e-02 +-2.3342466396229100e+00 +5.6531007827645019e-01 +7.3636622839718516e-02 +-2.7170988648175500e+00 +1.5614981657516018e+00 +6.9537319332899722e-02 +-2.2241547345425925e+00 +1.5500632403056518e+00 +6.9820179141013405e-02 +-2.2209767642137330e+00 +6.0026395819564737e-01 +7.6172494149536807e-02 +-2.7566679623979926e+00 +1.5453496423921786e+00 +1.0575047522084829e-01 +-2.2268607712393678e+00 +7.9237791008782710e-01 +1.1578048468261525e-01 +-2.9399580054246548e+00 +1.6059459044072191e+00 +1.2300470129414835e-01 +-2.1971402411398917e+00 +1.6006205749580233e+00 +1.2300086682521473e-01 +-2.2034529423162872e+00 +1.5889903519224435e+00 +1.2295287752276887e-01 +-2.2011424384681115e+00 +1.5849631816233618e+00 +1.2625815323320980e-01 +-2.2020265776962962e+00 +1.6768286179265417e+00 +1.2621261425693747e-01 +-2.1488720438119921e+00 +1.4045246417699158e+00 +1.3558113922454595e-01 +-2.2703925660043520e+00 +2.0072862241971468e+00 +1.3652598820906944e-01 +-2.3140338672220522e+00 +4.0531213599633531e-01 +1.4938381174475182e-01 +-2.6543689658619143e+00 +3.4857985982933343e-01 +1.4997971396450485e-01 +-2.6508581022392632e+00 +1.4374709274489148e+00 +1.4146178325667511e-01 +-2.2197780629087651e+00 +1.5242247460250853e+00 +1.5639938051726621e-01 +-2.2568766522537969e+00 +1.5709298581077920e+00 +1.5998847189743903e-01 +-2.1936981686756600e+00 +5.1569926443410818e-01 +1.8202390860152737e-01 +-2.6852904543596252e+00 +5.1569926443410818e-01 +1.8202390860152737e-01 +-2.6852904543596252e+00 +3.5641592734019006e-01 +1.9039203301273508e-01 +-2.6594497872079739e+00 +1.5153502756969264e+00 +1.8731755931745273e-01 +-2.2233739673401520e+00 +-1.3054427882823427e-01 +2.2956399295731833e-01 +-3.4471905818961632e+00 +3.2728681825356531e-01 +2.1198789881596622e-01 +-2.6599683226498381e+00 +1.6040237359032168e+00 +2.0864744756096645e-01 +-2.1822569614503147e+00 +-2.7022973461025823e-01 +2.6097193992294837e-01 +-3.7121838350771714e+00 +1.5504850161440598e+00 +2.2830424398174201e-01 +-2.2218730960462256e+00 +1.5639909341993603e+00 +2.2883557657618742e-01 +-2.2089151616390801e+00 +1.6316305795120851e+00 +2.2912515160514976e-01 +-2.1627066267597561e+00 +3.5738897680002935e-01 +2.4218211246472479e-01 +-2.6618033799820071e+00 +1.5680580614870425e+00 +2.3242754633648530e-01 +-2.2078792248171566e+00 +1.6800030171399876e+00 +2.3330771288750685e-01 +-2.1148209389771351e+00 +1.6800030171399876e+00 +2.3330771288750685e-01 +-2.1148209389771351e+00 +4.5749332525535813e-01 +2.4943824705373246e-01 +-2.6552898464916495e+00 +1.6442841632423899e+00 +2.4241592959760114e-01 +-2.1582166897816402e+00 +1.5390877292010077e+00 +2.4565773166797605e-01 +-2.2592314008532344e+00 +1.5321795171840975e+00 +2.4569403252712921e-01 +-2.2596636252420432e+00 +4.1582457193958205e-01 +2.6510403989481973e-01 +-2.6574205174907974e+00 +4.2299128456958457e-01 +2.6345780453562312e-01 +-2.5490695933508234e+00 +1.4308166820669201e+00 +2.5862241820430593e-01 +-2.2174867282659068e+00 +1.4331509899729875e+00 +2.6958268886258380e-01 +-2.2202390264562295e+00 +4.8892299941033074e-01 +2.9513849493072175e-01 +-2.6833353246776799e+00 +-2.6211455628277858e-01 +3.5412203484978055e-01 +-3.7271773650742719e+00 +1.3763009002920679e+00 +3.0330604269966194e-01 +-2.2722818993388807e+00 +-2.9247775580003160e-02 +3.4438977449049119e-01 +-3.2425094996892239e+00 +1.4211329998667614e+00 +3.0448902664690269e-01 +-2.2376722648599405e+00 +-8.9618609723107506e-02 +3.6291496019222447e-01 +-3.3709154535406713e+00 +-8.6768105776566318e-01 +3.2176013842770135e-01 +-2.5649750632521688e+00 +-4.3825424294214790e-03 +3.7792418603049205e-01 +-3.1700905142182276e+00 +-1.1243606465652124e-01 +3.9209254692134327e-01 +-3.4229874804219005e+00 +3.6259306236274969e-01 +3.5776261875807885e-01 +-2.6582307916157992e+00 +3.9379095797825486e-01 +3.6166346452209319e-01 +-2.6503436397803188e+00 +2.8818281473867308e-01 +3.6362441124545447e-01 +-2.6780772577409411e+00 +-3.7184449262970584e-02 +3.9806185568296437e-01 +-3.2509137633550278e+00 +5.4064137975855064e-01 +3.6986757804484433e-01 +-2.7089117862701624e+00 +4.5379863129163678e-01 +3.6835819647747586e-01 +-2.6587220864878010e+00 +4.3940140327439026e-01 +3.6921957636878650e-01 +-2.6602116883124349e+00 +5.5457222658857297e-01 +3.7353319316489481e-01 +-2.7025548516028191e+00 +2.0187352687896674e+00 +4.0662907034305951e-01 +-2.8619699144721915e+00 +-1.5684305886863212e-01 +4.2372896650985586e-01 +-3.5026079672246042e+00 +-1.5690063701669127e-01 +4.2360585725722161e-01 +-3.5022731507876754e+00 +-2.4748358746163140e-01 +4.4072202736885341e-01 +-3.7087018454636147e+00 +-1.5810359623857684e-01 +4.2926811341791099e-01 +-3.4975649821562453e+00 +1.9210529184822125e+00 +4.1700113920231591e-01 +-2.9504335199234890e+00 +-1.2061228324210736e-01 +4.2625566489519723e-01 +-3.4322857653905436e+00 +-1.4609839904286712e-01 +4.3098281154694656e-01 +-3.4883829689313015e+00 +2.0858311807629253e+00 +4.2431775192405474e-01 +-2.7845937787230692e+00 +2.0052884387783498e+00 +4.2928712158661403e-01 +-2.8480040979945991e+00 +-2.4324673246744796e-02 +4.3443632096282842e-01 +-3.2218229392096869e+00 +1.1448936687148576e-02 +4.3684547648516703e-01 +-3.1394554943299795e+00 +3.6808681025464851e-03 +4.4235087454097949e-01 +-3.1614682385322381e+00 +9.2141690328701471e-03 +4.4197519054315587e-01 +-3.1422008470135889e+00 +2.0649787811766975e+00 +4.6119108089047278e-01 +-3.0240763640387569e+00 +-3.3629248094604047e-01 +4.9478246426189754e-01 +-3.8769268335215901e+00 +-2.9784036559279931e-01 +4.9251010866373740e-01 +-3.8074183784423630e+00 +-2.9784036559279931e-01 +4.9251010866373740e-01 +-3.8074183784423630e+00 +-2.7740713887365814e-01 +4.9598685025184386e-01 +-3.7958647367424461e+00 +-3.4640168363783108e-01 +5.0751885340504288e-01 +-3.8979680274069843e+00 +-7.3974410201468066e-01 +4.3847979374171137e-01 +-2.9834090411476906e+00 +5.9110320896858592e-01 +4.4098293569824509e-01 +-2.7565735498982131e+00 +2.0191628477864536e+00 +4.7621108769215009e-01 +-2.8592511899323338e+00 +2.0424886666080262e+00 +4.7666091824720397e-01 +-2.8516503155521709e+00 +2.0721240619630197e+00 +4.7547567033136501e-01 +-2.8154924600349367e+00 +-5.0573570559745186e-02 +5.0497953202841073e-01 +-3.5445487686897628e+00 +-5.2851220328156041e-02 +5.0516713092581667e-01 +-3.5315632634577132e+00 +5.0776744270255492e-01 +4.4410012288960232e-01 +-2.6893475410820882e+00 +3.0340124408656388e-01 +4.4016171980391455e-01 +-2.7027144253574167e+00 +-3.1018447887510864e-01 +5.3869590967475867e-01 +-3.8775104326590286e+00 +4.3323702669229375e-01 +4.5857319884429543e-01 +-2.6663536766214411e+00 +1.9443174574868911e+00 +5.1484626102513964e-01 +-2.8932791724895770e+00 +-5.4549248898961213e-02 +5.3583382308841687e-01 +-3.5444801696857935e+00 +-1.8976591366515392e-02 +3.0549484722551795e-01 +-7.4809201533727199e-01 +4.1252970619711515e-01 +5.7867906370179190e-01 +-3.5425405269545576e+00 +-1.0226836599740885e-01 +3.1375706297888795e-01 +-7.7088405021769535e-01 +-5.8537396493738951e-02 +6.0163887244070324e-01 +-3.6148376840803449e+00 +9.1218859031541769e-02 +5.6400335763976506e-01 +-3.1459508112309473e+00 +8.4339586719967441e-02 +5.6055102080546182e-01 +-3.1230141421621926e+00 +2.1798126333508611e-01 +5.6320769410240645e-01 +-3.0848352907731424e+00 +1.8938792637834062e-01 +5.8712853785666386e-01 +-3.0637587831031365e+00 +8.0183561109155671e-02 +6.0380489677070692e-01 +-3.1277969521986653e+00 +1.2930060677621361e-01 +6.1136394564861929e-01 +-3.0523092411791386e+00 +-3.7183062838949316e-01 +3.2353256890004941e-03 +-6.6653330214735829e-01 +-3.7183062838949316e-01 +3.2353256890004941e-03 +-6.6653330214735829e-01 +1.9893426313925981e+00 +-9.9330697072342405e-02 +-2.3353403646546576e+00 +1.9828566345779799e+00 +-8.7396382462879174e-02 +-2.3561169690988955e+00 +3.6553389172094708e-01 +-3.5137709167430232e-02 +-2.6306329363452181e+00 +1.6820873908001508e+00 +-4.0732796384662442e-02 +-2.1068128012666421e+00 +1.5151363204604842e+00 +-3.8429153488353344e-02 +-2.1182105804869846e+00 +1.4283815275592939e+00 +-4.0665974893912209e-02 +-2.2253461391866183e+00 +4.5756776783768710e-01 +-3.0514252408854473e-02 +-2.6506924164274377e+00 +1.4024668196515826e+00 +-2.8300512869153641e-02 +-2.0735801340655446e+00 +1.4486939726454222e+00 +-1.9842393658624780e-02 +-2.2081359011390593e+00 +1.5190536599526290e+00 +-3.8674075838169000e-03 +-2.1548881018022370e+00 +1.6161785600537741e+00 +2.4452232778243377e-02 +-2.1956340433905979e+00 +1.6106645493286706e+00 +3.9221258454311361e-02 +-2.1951925536267471e+00 +1.6106645493286706e+00 +3.9221258454311361e-02 +-2.1951925536267471e+00 +3.1116339540617316e-01 +5.2484268049024667e-02 +-2.6663951512367632e+00 +2.0096354303391508e+00 +5.8570533495049766e-02 +-2.3247375701569757e+00 +1.9867201981602074e+00 +5.8168690043042960e-02 +-2.3539913686161107e+00 +-8.0045116154654516e-01 +9.5625850386683725e-02 +-2.6320345567311820e+00 +1.6297704817476848e+00 +6.7080133269581538e-02 +-2.1618028731831971e+00 +3.6312293806272761e-01 +7.9559163799620261e-02 +-2.6577359670693683e+00 +1.4263768799831535e+00 +7.1132350837947209e-02 +-2.2383753553645653e+00 +1.6796625302887356e+00 +7.1524815522071725e-02 +-2.1091457527039497e+00 +1.6378759644572485e+00 +7.2534279340509447e-02 +-2.1544800680784340e+00 +1.4345034372510095e+00 +7.5981834228162320e-02 +-2.2223235040107783e+00 +1.9927109397656024e+00 +1.2393438734417499e-01 +-2.3479052324158096e+00 +1.0240975711150890e+00 +1.3412264645527591e-01 +-3.2120254946461930e+00 +1.5284427287161211e+00 +1.3306648772445068e-01 +-2.2607141031180982e+00 +1.4403267389665682e+00 +1.4596091683499549e-01 +-2.2289477414954670e+00 +2.0026281035553075e+00 +1.4511239839823914e-01 +-2.3190223114474584e+00 +1.4367740184601920e+00 +1.5483804034173418e-01 +-2.2251475104550038e+00 +4.1322003251165718e-01 +1.6529861746694732e-01 +-2.6599764633830651e+00 +4.1322003251165718e-01 +1.6529861746694732e-01 +-2.6599764633830651e+00 +1.6888100065528990e+00 +1.6006035097439433e-01 +-2.1240105231847100e+00 +1.9998850428561250e+00 +1.7526664710845577e-01 +-2.3154840478843273e+00 +3.5560200287059562e-01 +1.8552498481622826e-01 +-2.6575861571325587e+00 +3.0726489891994702e-01 +1.8584590958522404e-01 +-2.6754235218111750e+00 +1.5587133801854038e+00 +1.8131166194028261e-01 +-2.2232784830026695e+00 +1.6197251885857977e+00 +1.8202541426133095e-01 +-2.1535337398626346e+00 +5.6120214847632477e-01 +2.1040300588687541e-01 +-2.7234042955725379e+00 +1.6769437219036682e+00 +2.1338037522783806e-01 +-2.1089957789073370e+00 +1.6016124785301429e+00 +2.1721646749544757e-01 +-2.1807792466946032e+00 +1.5442821458029377e+00 +2.1995957040008421e-01 +-2.2329543504343197e+00 +-4.0557486883039076e-02 +2.5031352769116244e-01 +-3.2613518321239905e+00 +1.6501729772030886e+00 +2.2077891325330048e-01 +-2.1394625617013139e+00 +1.6501729772030886e+00 +2.2077891325330048e-01 +-2.1394625617013139e+00 +1.6478519405351348e+00 +2.2599410416401305e-01 +-2.1544285771001563e+00 +1.6596402211051318e+00 +2.2885911708134865e-01 +-2.1371749983700425e+00 +6.5724002007447602e-01 +2.5232610680954692e-01 +-2.8005358017885200e+00 +6.5724002007447602e-01 +2.5232610680954692e-01 +-2.8005358017885200e+00 +1.5445430010040839e+00 +2.4193012722836729e-01 +-2.2535175707624533e+00 +1.6618833643011908e+00 +2.4260927209167751e-01 +-2.1642317608330526e+00 +4.1003802184401961e-01 +2.5524273643704676e-01 +-2.6532322094665228e+00 +1.6731522342621075e+00 +2.4359943574352030e-01 +-2.1398380154129226e+00 +3.2867038331160409e-01 +2.5865021998521298e-01 +-2.6629936890572781e+00 +-1.9975731119000171e-02 +2.8051317822523397e-01 +-3.2141945122561641e+00 +-7.3248971778322247e-01 +2.6844467980187342e-01 +-2.7496663793946379e+00 +-2.8493795142716209e-02 +2.8595156432621521e-01 +-3.2120315927120862e+00 +-2.7133600970124544e-01 +3.0701834824242491e-01 +-3.7405323597559472e+00 +1.4348165082804232e+00 +2.6151562438950854e-01 +-2.2177353647200402e+00 +-2.8834837334115343e-01 +3.2035103319625230e-01 +-3.7666209028092190e+00 +1.3746860770681006e+00 +2.6944555188478309e-01 +-2.2755286385861351e+00 +-2.6299202976467390e-01 +3.2608409414634326e-01 +-3.7231960769075294e+00 +1.6824218378297300e+00 +2.6988189419065683e-01 +-2.1490906208114540e+00 +3.1665140598576164e-01 +2.8708590747319024e-01 +-2.6613723716733411e+00 +-1.7529564265412431e-01 +3.3260683529513879e-01 +-3.5449093322643499e+00 +1.4077886153528274e+00 +2.8189047394587508e-01 +-2.2320389930205393e+00 +1.6129157576023812e+00 +2.9657945242167882e-01 +-2.2546529748088919e+00 +-7.9897578951175552e-02 +3.7137512524134020e-01 +-3.3424096807853076e+00 +1.0052358549158587e+00 +3.7979121732011711e-01 +-3.3611534395932772e+00 +3.8819640658944038e-01 +3.4441339300007218e-01 +-2.6489838942592328e+00 +4.8063161645554070e-01 +3.5216331256936956e-01 +-2.6735419341863271e+00 +-5.2810826434670076e-02 +3.8499697321973625e-01 +-3.2968216283813407e+00 +-1.1873989244530304e-01 +3.9229717364610051e-01 +-3.4266278686206193e+00 +2.2635579325751837e-01 +3.5922414505675559e-01 +-2.7261553919989372e+00 +-2.5048730111818507e-01 +4.1613216033344119e-01 +-3.7019023042437458e+00 +-3.9304883141923083e-02 +2.3573714675507407e-01 +-6.8064103045980828e-01 +-5.2859117696326556e-02 +3.9441694198320887e-01 +-3.2979320108244359e+00 +4.7596864980918818e-01 +3.5979943538579195e-01 +-2.6663493614636580e+00 +2.6415189405821765e-01 +3.6323472008732383e-01 +-2.6788885676812662e+00 +-4.0454212825658385e-02 +3.9724353759370401e-01 +-3.2576598560703802e+00 +2.0165232981290067e+00 +3.9702169480838179e-01 +-2.8682874003373646e+00 +5.3868435306677076e-01 +3.7289825490303985e-01 +-2.6972055876014069e+00 +5.1669856999075703e-01 +3.7694550131769095e-01 +-2.6797672263057830e+00 +3.2507486485718690e-01 +3.8115175018604303e-01 +-2.6588178289070448e+00 +-3.9725989909991592e-02 +4.3307039106426048e-01 +-3.2608362558580550e+00 +3.1017050393164547e-01 +3.9833703562606032e-01 +-2.6760245339975883e+00 +-8.0735648995358732e-04 +4.3405959700862623e-01 +-3.1681310485813925e+00 +1.4291981488558311e-02 +4.3256859822091304e-01 +-3.1354820390246121e+00 +3.1473312524587793e-01 +4.0786053387735105e-01 +-2.6774319084508633e+00 +1.8597990660503182e-02 +4.3857173670843191e-01 +-3.1313239913262403e+00 +1.9087676629830079e+00 +4.5602099126276185e-01 +-2.9504783904977128e+00 +1.9917515771992398e+00 +4.5927266222049878e-01 +-2.9010382847691578e+00 +-3.1876612491628797e-01 +4.9670483118432140e-01 +-3.8456509995693748e+00 +2.8545520245995554e-01 +4.2013287345851091e-01 +-2.7018326139015265e+00 +2.0124706971157700e+00 +4.6173142948106771e-01 +-2.8603665256747215e+00 +2.0342568757840489e+00 +4.6208499043326839e-01 +-2.8235253759263457e+00 +-2.7374979726716442e-01 +5.0110544358118225e-01 +-3.7539391753317592e+00 +2.4586169103603311e-02 +4.5885042283033839e-01 +-3.1102646084997909e+00 +2.4586169103603311e-02 +4.5885042283033839e-01 +-3.1102646084997909e+00 +4.2908372469154283e+00 +6.6475812312258464e-01 +-4.8382804615584432e+00 +1.9893615215623632e+00 +4.7516432553886723e-01 +-2.8498668974763111e+00 +1.9893615215623632e+00 +4.7516432553886723e-01 +-2.8498668974763111e+00 +4.8805218659697663e-01 +4.4036361028940701e-01 +-2.6687961328692369e+00 +2.8278273999385278e-01 +4.4234303458949525e-01 +-2.7001557921708752e+00 +2.1898753311831927e+00 +4.8201933042315143e-01 +-2.7344047333119632e+00 +2.1780656122574538e+00 +4.8228706669903598e-01 +-2.7372328498572096e+00 +1.3823554255883946e-01 +4.5887563468919190e-01 +-2.8641615861087666e+00 +-2.1364723622237969e-01 +5.3132592647194254e-01 +-3.7190038526013574e+00 +3.6689260957502989e-01 +4.5456128254547135e-01 +-2.6517902331323016e+00 +4.2959862872004457e+00 +7.2583765352472129e-01 +-4.8286600114252431e+00 +-1.5739030921761765e-01 +5.7086888692536164e-01 +-3.6495653459495174e+00 +2.0335477000820386e+00 +5.5319371640680570e-01 +-2.9006127119328031e+00 +-9.6507560666160300e-02 +3.1779601833361854e-01 +-7.7563173480395098e-01 +2.7533796730749205e-01 +5.5468062233478233e-01 +-3.1080673046912448e+00 +2.2203457123017362e-01 +5.5860314768418318e-01 +-3.1074903873585802e+00 +2.3151118506485427e-01 +5.6753673458019571e-01 +-3.0884696780246519e+00 +1.6158582607647520e-01 +5.8144883530140334e-01 +-3.0520667718847831e+00 +1.8264550772741819e-01 +5.8432395631220224e-01 +-3.0611407821342871e+00 +1.3237976831798623e-01 +5.8405160587687988e-01 +-3.0489768554483674e+00 +1.3400347270934018e-01 +5.8636354797841383e-01 +-3.0442082557746990e+00 +1.3294108612711400e-01 +5.8990752239737798e-01 +-3.0453447262274169e+00 +-1.0916305958850855e-01 +6.6459959353236053e-01 +-3.7630649891838490e+00 +-1.1883173203785112e-01 +6.6436017242569789e-01 +-3.7578386614007635e+00 +-1.2590864782733430e-01 +6.6518746768473669e-01 +-3.7546017012672581e+00 +2.0206576488365208e-01 +6.0318840185989586e-01 +-3.0788598611534268e+00 +1.8448432246765445e+00 +4.5803695438625891e-01 +-4.5664752824444870e+00 +1.8321306819988714e+00 +4.9450180780169289e-01 +-4.5758716332899860e+00 +4.5202499963571496e-01 +3.7764538910271667e-01 +-2.6511314603299003e+00 +1.3674748329011523e+00 +9.9627052639083294e-02 +-2.3094939025278114e+00 +2.9714602921227597e+00 +5.8938133248898339e-01 +-6.6621553179423865e+00 +1.7837273881813102e-02 +4.0252161071958820e-01 +-3.1206683473758039e+00 +2.4784099634382017e+00 +2.2328518721926849e-01 +-2.3959610481502001e+00 +-1.5678747474124957e-01 +2.9091518415420814e-01 +-3.5040425793023324e+00 +-2.3172914024966627e-03 +4.2064434427209779e-01 +-2.6672246940313324e+00 +-2.6656976350476430e-01 +4.5611784350834739e-01 +-3.7214432805431055e+00 +1.6838451823216816e+00 +6.0745158183324746e-03 +-2.1677873918648669e+00 +1.7168974251533393e+00 +5.3846638895210186e-02 +-2.2035100709586328e+00 +2.4286160361089753e+00 +1.2236297783365156e-01 +-2.3857057796880152e+00 +2.5668853277524675e+00 +1.9853738761665041e-01 +-2.6546163422121980e+00 +2.8964242828442810e+00 +2.7779869693370002e-01 +-2.9028071238510447e+00 +-1.2179054490355506e-01 +3.8615134437607046e-01 +-3.4417305696965355e+00 +-1.2720131069995883e-01 +8.3826154506107114e-02 +-7.1987791000669221e-01 +1.6663506932109611e+00 +1.6762348067555170e-02 +-2.1167188042996963e+00 +1.7009493731526750e+00 +1.1148110590182279e-01 +-2.1529268036157476e+00 +2.6109495751205380e+00 +8.9357411860503708e-02 +-2.8533849963487059e+00 +2.4773458522959504e+00 +1.5801485928269007e-01 +-2.4270856695072340e+00 +2.4570975812414573e+00 +1.8835327622457346e-01 +-2.3939473397946966e+00 +2.4623244088842604e+00 +2.4365286781497708e-01 +-2.3851357279352929e+00 +3.7440719942194549e-02 +3.8718181939405094e-01 +-3.1176517667686583e+00 +4.6147897211873339e-02 +4.0051172213578856e-01 +-3.0721869436839486e+00 +1.5702747192485267e+00 +-2.2960213093445647e-02 +-2.1557806907747397e+00 +1.1667859754323213e+00 +3.5623350430201470e-02 +-1.7754712066443232e+00 +8.0896119082296514e-01 +3.3119044610841905e-02 +-2.9468976206938673e+00 +2.5418700675379080e+00 +1.3065464071642122e-01 +-2.4321695497535449e+00 +3.7600657920537928e-01 +1.9768159759472190e-01 +-2.6248905570057977e+00 +2.4746165975527492e+00 +1.8256120669561263e-01 +-2.4550888802099218e+00 +-1.3753762376076498e-01 +2.8105752802813866e-01 +-3.5150821511782788e+00 +1.4327018709880295e+00 +2.9576169944290370e-01 +-2.2369793486263565e+00 +2.9618589031315374e+00 +3.2371987185875961e-01 +-3.1547689075439278e+00 +3.9964063590640025e-01 +4.4614001161556899e-01 +-2.6676435660304119e+00 +-1.6967427731372539e-01 +5.7247499622789821e-01 +-3.6406833748244174e+00 +-9.6027516482861175e-01 +6.8784505126344066e-03 +-1.7089844508322155e-01 +1.4529033510212539e+00 +-1.3748518301630127e-02 +-3.7818177666285440e+00 +1.5579811685934659e+00 +1.1159488744238720e-01 +-3.9159774280009634e+00 +1.6034763235601350e+00 +1.6791872790968018e-01 +-2.2048666416949021e+00 +2.4387376160847265e+00 +1.8439083991317273e-01 +-2.4572284320096420e+00 +1.6870953888483544e+00 +2.0477719769600194e-01 +-2.1843189795369802e+00 +1.6870953888483544e+00 +2.0477719769600194e-01 +-2.1843189795369802e+00 +2.4566713016227428e+00 +2.0932375205007109e-01 +-2.3896895543742849e+00 +3.0460764868730781e+00 +2.1517134146625561e-01 +-3.1984876801541264e+00 +2.4521198418900254e+00 +2.3243768024132810e-01 +-2.4287767694787439e+00 +-3.0421608367546771e-01 +2.8405341125348998e-01 +-3.8299201097587550e+00 +-2.7832156676662628e-01 +2.8630378380817900e-01 +-3.7589821499490896e+00 +2.4618511103604575e+00 +2.4797765196624777e-01 +-2.4154439448245690e+00 +-8.7140336353568670e-01 +2.8002735266834777e-01 +-1.1265669617370717e+00 +-8.7140336353568670e-01 +2.8002735266834777e-01 +-1.1265669617370717e+00 +2.7120879252360917e+00 +3.0160748951303101e-01 +-2.6995990580519234e+00 +3.7207121211700661e-01 +3.5841466242885922e-01 +-2.6510446519038702e+00 +4.6467493147419360e-02 +4.3284622702178260e-01 +-3.0722827896221001e+00 +-2.7767070809455624e-01 +4.8917019292577646e-01 +-3.7402835279887370e+00 +-3.1294921924649755e-01 +5.6664413003660519e-01 +-3.8071688672725821e+00 +2.6526336327524774e-01 +5.4145980958611339e-01 +-3.0858665437297095e+00 +5.5166884139906847e-01 +-8.6338098472806324e-02 +-2.7362963209021807e+00 +1.5932757284718517e+00 +6.3813578647897388e-03 +-2.2075274754106262e+00 +5.9766630777126284e-01 +1.7089813837946866e-01 +-2.7652750020277841e+00 +5.9766630777126284e-01 +1.7089813837946866e-01 +-2.7652750020277841e+00 +1.3993668697966755e+00 +2.0891262927331394e-01 +-2.2565059407240384e+00 +2.4736739249051123e+00 +2.4299251408850947e-01 +-2.3619268122480319e+00 +2.4736739249051123e+00 +2.4299251408850947e-01 +-2.3619268122480319e+00 +5.7246065124051748e-01 +2.7643314802873792e-01 +-2.7182875855835933e+00 +2.9810260728539437e+00 +2.6679782456554418e-01 +-3.1705799204740202e+00 +2.7343305801809326e+00 +2.8314147509450954e-01 +-2.6443832343191342e+00 +2.7343305801809326e+00 +2.8314147509450954e-01 +-2.6443832343191342e+00 +2.7736764136521401e+00 +2.8835207687796327e-01 +-2.6997947334643939e+00 +2.8091859790473768e+00 +3.0273610636364884e-01 +-2.6540390434686043e+00 +-9.7622386516501014e-02 +3.8421977261822632e-01 +-3.4026201217170295e+00 +-2.6960162779508540e-01 +4.4336386303293990e-01 +-3.6601053393242817e+00 +2.9660409020232463e+00 +4.5291321326048845e-01 +-3.1614527650372448e+00 +-3.1205902942263289e-02 +5.2786082275998747e-01 +-3.5360313156192307e+00 +-9.5899130412129496e-01 +1.0127061569813765e-02 +-1.7575401559154494e-01 +4.0450661120433645e-01 +7.1636912716303083e-02 +-2.6735004056272307e+00 +2.4379522607420339e+00 +1.5270645274632108e-01 +-2.4172666116076496e+00 +1.6538199345047366e+00 +1.8181816993237920e-01 +-2.1796037996142719e+00 +-1.1750909796041888e-01 +2.3756585596881466e-01 +-7.1856266907936672e-01 +-1.1750909796041888e-01 +2.3756585596881466e-01 +-7.1856266907936672e-01 +-1.2954952916006304e-01 +2.3744911926819653e-01 +-7.3110018530151610e-01 +2.9406890748938856e+00 +2.4059022641325600e-01 +-3.1932840539800713e+00 +6.9157653146291753e-01 +2.8804314099107975e-01 +-2.8600212524103936e+00 +2.7722915768403258e+00 +3.0342733792013243e-01 +-2.6619544369626422e+00 +1.8079987420791728e+00 +3.3903934191332569e-01 +-4.3873029452720829e+00 +-3.4187763717970121e-01 +3.8755637760234707e-01 +-3.8720522684217262e+00 +-3.4187763717970121e-01 +3.8755637760234707e-01 +-3.8720522684217262e+00 +-3.1486175512466463e-01 +3.8925084580579355e-01 +-3.8215670760818088e+00 +-2.9930778010343762e-01 +3.9051572083599334e-01 +-3.7810240338334511e+00 +-7.4422372054563188e-02 +3.9365104043498217e-01 +-3.3770262934786377e+00 +2.0489038321873387e+00 +4.4291467860053957e-01 +-2.8694742653699237e+00 +-2.8448947309723321e-01 +4.8071926736759552e-01 +-3.7544334163664845e+00 +1.9196876605233554e-01 +5.3963973609443017e-01 +-3.0555702942133109e+00 +5.0265434344642856e-01 +-5.1781319651776639e-02 +-2.6827342240853129e+00 +5.3270804804810912e-01 +-3.8984315992229124e-02 +-2.6904012562885664e+00 +2.0618354629404707e+00 +-6.3221095592227203e-02 +-2.3770046911972247e+00 +1.5540769898592319e+00 +-1.9650755040205727e-02 +-2.1558115696031628e+00 +1.5540769898592319e+00 +-1.9650755040205727e-02 +-2.1558115696031628e+00 +1.3923922235733501e+00 +5.2390490069528478e-02 +-2.2615130696712593e+00 +1.0640124647829692e+00 +1.1203252308744545e-01 +-3.2471111173663343e+00 +1.4403056556693754e+00 +1.2069184157666807e-01 +-3.7805012863119702e+00 +8.5760978974125157e-01 +1.4701582780001554e-01 +-2.9975252639286207e+00 +2.5440953097066776e+00 +1.2289788505207558e-01 +-2.5797395750415695e+00 +2.4789350279940319e+00 +1.2697427545305798e-01 +-2.4837235269608664e+00 +2.5195729581908202e+00 +1.2530559502053557e-01 +-2.5392738168350464e+00 +4.1406725537086086e-01 +1.8905613857214032e-01 +-2.6496849659911872e+00 +3.0014920623212737e+00 +2.2478041697751103e-01 +-3.1745274109286501e+00 +2.9669843601366424e+00 +2.4170279451539520e-01 +-3.1860552560513162e+00 +2.4930286256745608e+00 +2.5365341303902933e-01 +-2.3931228033544354e+00 +2.9737691999074767e+00 +3.3311339418573582e-01 +-3.2194796904601426e+00 +2.9967028332821721e+00 +3.3714965821417048e-01 +-3.1624173380626175e+00 +2.9943532601301133e+00 +3.3859518418052054e-01 +-3.2131254416279305e+00 +2.8863831985227861e+00 +3.4525864834789549e-01 +-3.1515067453023784e+00 +2.9776479293513241e+00 +3.4799727845707507e-01 +-3.1924428860728873e+00 +3.0067247407144406e+00 +3.4994481802124844e-01 +-3.1642257886767959e+00 +3.0067247407144406e+00 +3.4994481802124844e-01 +-3.1642257886767959e+00 +2.8526954803172808e+00 +3.6436378830713489e-01 +-3.1189087909904933e+00 +2.9543091633073084e+00 +3.6684433094329039e-01 +-3.1468118936279521e+00 +2.9822856261220259e+00 +3.9649309483323064e-01 +-3.1910578790477118e+00 +1.9927466274449757e+00 +3.9183063973384480e-01 +-2.9307817568374350e+00 +1.9858101179825520e+00 +3.9199524754023485e-01 +-2.9432672608777923e+00 +1.9679881579577796e+00 +4.3293876862838310e-01 +-2.9033280767058156e+00 +2.9672336567443605e+00 +4.6426536978098248e-01 +-3.2166613110819120e+00 +1.9677742822542044e+00 +4.4615563397801350e-01 +-2.9032664932474672e+00 +2.0824185614161439e+00 +4.5866016457454828e-01 +-2.8248103033469163e+00 +-1.8019857185269109e-02 +5.0424329592373551e-01 +-3.5426385279572914e+00 +2.6167768339499764e-01 +5.5245565780338535e-01 +-3.0998542071484541e+00 +7.3498972858643141e-01 +-3.1300454616800216e-03 +-2.9743764126318855e+00 +2.4778409904510070e+00 +2.3824252922968560e-02 +-2.4137791307546315e+00 +2.6143578809604033e+00 +6.4379471178859102e-02 +-2.6628542444290453e+00 +1.5295580459440614e+00 +1.0803820269592986e-01 +-2.2675607977206473e+00 +2.5783044864469642e+00 +1.1980126992446406e-01 +-2.6304546065801331e+00 +2.6872439004492117e+00 +1.2039552703774278e-01 +-2.7667540341237071e+00 +2.6872439004492117e+00 +1.2039552703774278e-01 +-2.7667540341237071e+00 +2.6636710566293003e+00 +1.2224784520663336e-01 +-2.7359268448493412e+00 +2.6636710566293003e+00 +1.2224784520663336e-01 +-2.7359268448493412e+00 +2.6566066298296294e+00 +1.3009011489352659e-01 +-2.7568678343379895e+00 +2.6566066298296294e+00 +1.3009011489352659e-01 +-2.7568678343379895e+00 +2.6236640095384560e+00 +1.3430624379827011e-01 +-2.7085232752383965e+00 +2.6236640095384560e+00 +1.3430624379827011e-01 +-2.7085232752383965e+00 +2.4499155189171025e+00 +1.4463580954336683e-01 +-2.4411217092063509e+00 +2.6843088357925078e+00 +1.3981935492442810e-01 +-2.7828499456343252e+00 +2.9837896215393536e+00 +1.5220683272563640e-01 +-3.1534301175557231e+00 +1.2182162399638170e+00 +1.9318001560901493e-01 +-3.4730574027381960e+00 +1.4836185754988656e+00 +2.0036478838561797e-01 +-2.2221222137625327e+00 +8.7696989404077463e-01 +2.0810159992817676e-01 +-3.0330596689999263e+00 +1.5555412886901683e+00 +1.9969674965004952e-01 +-2.2298487065814099e+00 +-1.3456107199349937e-01 +2.3959054680784295e-01 +-7.3153304364617422e-01 +-1.3456107199349937e-01 +2.3959054680784295e-01 +-7.3153304364617422e-01 +7.5168890915610775e-01 +2.3738748381548996e-01 +-2.8984709338201373e+00 +2.9853893733891605e+00 +2.0963431573898644e-01 +-3.1741460013535856e+00 +2.9853893733891605e+00 +2.0963431573898644e-01 +-3.1741460013535856e+00 +-3.0990848598992987e-01 +2.6874433442937440e-01 +-3.8511850290158161e+00 +2.9588301472752812e+00 +2.2464299537877336e-01 +-3.1499162808931085e+00 +2.9588301472752812e+00 +2.2464299537877336e-01 +-3.1499162808931085e+00 +2.9427559143029556e+00 +2.2427588317301342e-01 +-3.1935275122149962e+00 +1.5366923648486601e+00 +2.4305354620613193e-01 +-2.2760005283625082e+00 +2.4697176247358810e+00 +2.4683812869158878e-01 +-2.4077419125043447e+00 +-8.0397576920368766e-02 +2.8754097548901741e-01 +-3.3602648674676665e+00 +2.9975344776882387e+00 +2.8561715457260034e-01 +-3.1532339781574716e+00 +3.0476978136776829e+00 +3.7763746791796610e-01 +-3.1695858001812072e+00 +5.9063749672383381e-01 +3.7675745933121951e-01 +-2.7336151407993992e+00 +2.9660471418486645e+00 +3.9409267625085204e-01 +-3.2124711171359506e+00 +2.9890662783735320e+00 +4.0151917580019436e-01 +-3.2085568510118638e+00 +2.9835282776338654e+00 +4.0636499183661073e-01 +-3.2450324704936477e+00 +2.0625063635807699e+00 +4.3019445767052972e-01 +-2.8459407153894563e+00 +2.0098897958512421e+00 +4.3102510192952892e-01 +-2.8658922532447368e+00 +4.8709700101195391e-01 +-8.0822929673003335e-02 +-2.6922758550272348e+00 +4.8905313790121729e-01 +-7.6274785818219393e-02 +-2.6841372789254159e+00 +4.7421380525881257e-01 +-7.5086341083676317e-02 +-2.6701790209187268e+00 +1.6674254443053984e+00 +2.5182453388586969e-02 +-2.1600113410043158e+00 +1.6776535233033429e+00 +2.5415241729567380e-02 +-2.1515494458622593e+00 +1.5555774702587324e+00 +1.2841161025440834e-01 +-3.9350770272320901e+00 +1.5555774702587324e+00 +1.2841161025440834e-01 +-3.9350770272320901e+00 +1.4648595557484556e+00 +1.5686924412633932e-01 +-2.3117691876735962e+00 +2.7404250621555213e+00 +1.5221009908797153e-01 +-2.8441615315256827e+00 +2.7213890727873040e+00 +1.5476190876031332e-01 +-2.8074303666343452e+00 +1.2536489964219042e+00 +1.9423598024883607e-01 +-3.5179296010297203e+00 +1.2536489964219042e+00 +1.9423598024883607e-01 +-3.5179296010297203e+00 +6.6028924795416211e-01 +2.6259511975396915e-01 +-2.8049438628790742e+00 +2.5063110670143569e+00 +2.3776128769853797e-01 +-2.4997565561628114e+00 +2.4751721575034340e+00 +2.4162677332445592e-01 +-2.3736209446780396e+00 +2.4545322268983245e+00 +2.5526828486891745e-01 +-2.3900193456473695e+00 +2.4877390743751135e+00 +2.5657788090308442e-01 +-2.3775035169759042e+00 +2.9441269131938990e+00 +2.8761832331558840e-01 +-3.1112821607277152e+00 +2.9441269131938990e+00 +2.8761832331558840e-01 +-3.1112821607277152e+00 +1.3747419140046757e+00 +3.0363856032072090e-01 +-2.3093758496737213e+00 +9.9577206614766289e-01 +3.8878938936268459e-01 +-3.2855791028376706e+00 +9.9422466884444849e-01 +3.8919949740120685e-01 +-3.3002604098218624e+00 +2.9792414074651843e+00 +3.9849763990979487e-01 +-3.2093746344021179e+00 +2.9599112776102467e+00 +4.1230560196698324e-01 +-3.2323177793873135e+00 +2.0233052011253321e+00 +4.3415156727882298e-01 +-2.8512043316315974e+00 +3.3322755719080088e-01 +4.3556000993902672e-01 +-2.6600504630033086e+00 +1.3386034993465731e-01 +4.4486647932258871e-01 +-2.8853884075804999e+00 +2.7045599961735051e-01 +4.4963710483378322e-01 +-2.6912979352258133e+00 +2.7045599961735051e-01 +4.4963710483378322e-01 +-2.6912979352258133e+00 +-7.7407700345923799e-02 +4.8494247355235165e-01 +-3.5150505228469280e+00 +1.9450673089988677e+00 +5.0544817568519995e-01 +-2.9118435548766284e+00 +1.9856169686043339e+00 +5.1550270631907114e-01 +-2.8998502809217874e+00 +-3.3935813499053386e-01 +5.7270869076271136e-01 +-3.8765878932104276e+00 +1.2837155682593954e-01 +6.1079458654496288e-01 +-3.0504198383064338e+00 +1.5063935789409659e+00 +-2.6690324419253644e-02 +-2.1048586908173852e+00 +1.5134540038682582e+00 +-6.3232925992812552e-03 +-2.1440924335272031e+00 +1.5134540038682582e+00 +-6.3232925992812552e-03 +-2.1440924335272031e+00 +8.1380420126188968e-01 +2.3944282478225231e-02 +-2.9571109620076648e+00 +6.3194111411123666e-01 +6.2272251819885487e-02 +-2.7751304626081716e+00 +3.3670418925836010e-01 +9.2989981106026839e-02 +-2.6559428827658267e+00 +1.6465987608321326e+00 +7.0596265261780811e-02 +-2.1711343502546767e+00 +2.0323845855575740e+00 +1.0682103924664668e-01 +-2.3590289567434954e+00 +-1.3298890823904277e-01 +2.2294874262634201e-01 +-7.3254114668186021e-01 +2.6121240004739903e+00 +1.6249843828389751e-01 +-2.6519745036875277e+00 +2.5092921697444046e+00 +1.7036739512344803e-01 +-2.5036425868773371e+00 +1.7068304294511059e+00 +2.0033083936618704e-01 +-2.1469313079435159e+00 +9.6334015923520677e-01 +2.1131575386277165e-01 +-3.1229420734136184e+00 +7.7883336004632220e-01 +2.2624345985642286e-01 +-2.9177491478514672e+00 +1.6254683648098978e+00 +2.1695852446689895e-01 +-2.2061680659564846e+00 +1.5283421655944316e+00 +2.2651708164622891e-01 +-2.2732937781466847e+00 +4.8736129407526518e-01 +2.6120753713193690e-01 +-2.6708654535083114e+00 +2.0264130726586562e+00 +2.9965754208392170e-01 +-2.4779402708430198e+00 +1.9191058234629990e+00 +3.7893292425333991e-01 +-2.8898270520215590e+00 +-1.2209102328443001e-01 +4.0512715826325091e-01 +-3.4439599053118943e+00 +1.9689790091058561e+00 +4.0270694875369295e-01 +-2.9426194348547976e+00 +1.9504175241560924e+00 +4.5207930405751751e-01 +-2.8932125665853583e+00 +2.0089261016164159e+00 +4.9807390076216856e-01 +-2.9033285642545712e+00 +-4.2135664368207322e-02 +5.5797347411412135e-01 +-3.5704768063313925e+00 +2.6773611327981967e-01 +5.5983005293858079e-01 +-3.1050678498768169e+00 +5.2739542100712322e-01 +-5.3691692784916083e-02 +-1.8481425792607089e+00 +1.4489339489490767e+00 +-2.8875547764305051e-02 +-2.1132104549717501e+00 +1.5443576228747986e+00 +7.4260313165520758e-02 +-2.2071303800516962e+00 +2.0558611761806720e+00 +9.8823042773663050e-02 +-2.3820066840284770e+00 +5.7465703069417551e-01 +1.8125030737175460e-01 +-2.7301185742565921e+00 +1.6420031225890108e+00 +2.4259962415268457e-01 +-2.2393033730425871e+00 +4.0873686982857849e-01 +3.5504115371399975e-01 +-2.6548739029678203e+00 +2.1201594801920902e+00 +4.1982502000960242e-01 +-2.8065322705676783e+00 +4.6169800825569818e-01 +2.2807749411532141e-01 +-2.6606839082839260e+00 +4.6169800825569818e-01 +2.2807749411532141e-01 +-2.6606839082839260e+00 +-1.4259263850039422e-01 +4.9454481199776817e-01 +-3.5522305319802707e+00 +6.0191031581855903e-01 +-8.5750924255711902e-02 +-2.7439597138063183e+00 +-4.2641742057465126e-01 +4.0419214787114979e-02 +-6.5766841624173900e-01 +9.2108043582119903e-01 +1.0430404582444938e-01 +-3.0843797180140204e+00 +7.0186744873760898e-01 +2.8399609766298212e-01 +-2.8442356537134188e+00 +4.3943886935517756e-01 +3.1581932825069975e-01 +-2.6434675667975553e+00 +-5.8569110573729967e-02 +4.0850297712569467e-01 +-3.3005791826458841e+00 +5.1191275839542938e-01 +4.3799627557430665e-01 +-2.6971342875335815e+00 +-1.8597088305807093e-02 +5.1420564110667344e-01 +-3.5387699837958824e+00 +5.1138342032166439e-01 +-2.8542050112064822e-02 +-2.6879864110786302e+00 +1.2036827235829031e+00 +1.9198929771907405e-01 +-3.4502285642088824e+00 +1.2069063706178724e+00 +2.2411513623737225e-01 +-3.4510664072400226e+00 +5.5556716786083582e-01 +-5.3607684140060959e-02 +-2.7114581108870235e+00 +5.3182830944168380e-01 +-2.0523643192718538e-03 +-2.6899591706187547e+00 +1.5702211587709753e+00 +9.7697264639587875e-02 +-3.9354123259864786e+00 +1.0593981782944462e+00 +2.5017197709941363e-01 +-3.2384604685302576e+00 +8.2301492845697177e-01 +2.6135662394633163e-01 +-2.9608951517463495e+00 +8.0638172653170437e-01 +2.6641328208330051e-01 +-2.9431552005197337e+00 +5.8188389432339838e-01 +4.4787088650900453e-01 +-2.7231808908394171e+00 +1.0391987126488225e-01 +5.2342830918333216e-01 +-3.0190090439810211e+00 +7.6511496884999280e-02 +5.9915892569588236e-01 +-3.1406253428622968e+00 +6.2209821520998931e-01 +-3.7425464804449533e-02 +-2.7702872616329781e+00 +8.1273182046990156e-01 +2.1167905135036114e-01 +-2.9568961939530447e+00 +1.4832118976300504e-01 +5.9158408473181601e-01 +-3.0439899934567043e+00 +5.9413131950479969e-01 +-5.6105577284022198e-02 +-2.7432603037216006e+00 +3.7368675457407613e-01 +7.7102702590782335e-02 +-2.6351393409249209e+00 +5.1774393454446399e-01 +2.6024255555939235e-01 +-2.6852365561092362e+00 +4.8726194385777571e-01 +2.6161752150288814e-01 +-2.6698375129774878e+00 +5.4143006823099016e-01 +3.3091423228146544e-01 +-2.6988800596457772e+00 +-1.6951185785947515e-01 +6.0043320198224948e-01 +-3.7315368624925149e+00 +-9.8292077760708318e-01 +3.3852607745045105e-01 +-2.3988752525114903e+00 +-8.7900316226334707e-01 +5.7183107371171527e-01 +-2.5005837024926838e+00 +1.8429387095137013e+00 +3.7946501843228347e-01 +-4.6417086959514213e+00 +-1.1341515084889713e+00 +5.5058897615538130e-02 +-2.4102407632104867e+00 +1.2748938582340634e+00 +1.2253501108226182e-01 +-2.3664576270875446e+00 +1.8711111472343092e+00 +2.4492015537776265e-01 +-4.6464431911145763e+00 +1.8184682431231307e+00 +3.2957465315996065e-01 +-4.6892007449941451e+00 +-1.7019519853653389e+00 +2.9974691166312534e-01 +-2.9399188734165560e+00 +-1.1704242963111395e+00 +3.4260187032795408e-01 +-2.3778089787879826e+00 +-9.6543643612579033e-01 +4.9764878208168134e-01 +-2.9172494145429444e+00 +-1.1058482631463251e+00 +4.4794122235133521e-01 +-2.3934485468839588e+00 +-7.9896191773697667e-01 +6.1324738438709425e-01 +-2.5924916873458033e+00 +-1.1929205513344467e+00 +5.9657751530362524e-01 +-2.3917256488380874e+00 +-1.2851564234365274e+00 +6.2356442978607662e-01 +-2.3917893897255098e+00 +-1.2755338307859774e+00 +6.1884575184947888e-01 +-2.3646972615840229e+00 +-1.0535793087203198e+00 +6.4835937060785909e-01 +-2.4141638903026625e+00 +-1.1224972468393524e+00 +6.4355761915085619e-01 +-2.3719103176594145e+00 +-1.1986754349243980e+00 +6.5221061658456980e-01 +-2.3487423182223504e+00 +-1.2635929306854199e+00 +6.7802323544851983e-01 +-2.3751290513178751e+00 +-1.1516799227356564e+00 +6.8438287514969864e-01 +-2.3760672990586271e+00 +1.8541617200762321e+00 +3.8111593237477215e-01 +-4.6227245960490242e+00 +1.2141669106980617e+00 +2.9560597787129583e-01 +-3.5453890155805197e+00 +1.2453792567617188e+00 +1.9463868754469626e-01 +-2.2500076009085848e+00 +-1.1085136966757114e+00 +2.3123723839814087e-01 +-2.3832585377427327e+00 +-7.7649669323460668e-01 +3.2516405313377716e-01 +-2.6242038630751687e+00 +-9.1745628192958861e-01 +4.4016624448563885e-01 +-2.9439572385997139e+00 +-1.1942723593471294e+00 +5.6009349395964614e-01 +-2.3905470154793886e+00 +-1.1426404204594802e+00 +5.5525391601941776e-01 +-2.3673000133887649e+00 +-1.3448817410366962e+00 +5.8995855894586402e-01 +-2.3933029470217875e+00 +-1.1882652709940129e+00 +6.4364678379748153e-01 +-2.3734980758860678e+00 +-1.2281492422091480e+00 +6.4283373626392792e-01 +-2.3751172104486389e+00 +-1.1870079680875141e+00 +6.8170214634239834e-01 +-2.3741926559062216e+00 +-1.2131093815031184e+00 +7.1775899922740216e-01 +-2.3976911769948646e+00 +-1.2131093815031184e+00 +7.1775899922740216e-01 +-2.3976911769948646e+00 +-7.7510695434778332e-01 +3.3491396174909360e-01 +-2.7432554752167264e+00 +-8.3859931064508464e-01 +3.1127000759293511e-01 +-2.5472534101984916e+00 +-1.2278362184874985e+00 +2.9005238963509083e-01 +-2.3500485814092498e+00 +-1.1365508408297060e+00 +3.2888824214603840e-01 +-2.3520496713238948e+00 +-1.0374188127822854e+00 +4.0798584822222544e-01 +-2.3966736560860769e+00 +-1.1032160530875443e+00 +4.8007958087351504e-01 +-2.3897732624798111e+00 +-1.0995984590725638e+00 +5.0684700494978685e-01 +-2.3698078199633379e+00 +-1.1027433112985401e+00 +6.6287592188289712e-01 +-2.3361754498895237e+00 +-1.1970228034727115e+00 +7.7981168271609180e-01 +-2.3601057061697963e+00 +-9.2158462249293782e-01 +3.3663588853813453e-01 +-3.0312121314306344e+00 +-7.4603785339392858e-01 +3.2070869425862053e-01 +-2.7690668350088301e+00 +-7.0699919930755828e-01 +3.5477464524804714e-01 +-2.7809857814940391e+00 +-1.1073016272073821e+00 +4.9331703822237283e-01 +-2.3644480336315703e+00 +-7.8330703632634335e-01 +7.4873019136247887e-01 +-2.9113255408434369e+00 +-1.2623355376492702e+00 +6.5136170249911751e-01 +-2.3744710724916800e+00 +-1.2623355376492702e+00 +6.5136170249911751e-01 +-2.3744710724916800e+00 +-1.1535352537375443e+00 +6.5200370015222919e-01 +-2.3705457773577221e+00 +-1.1429181195085516e+00 +6.6225105297743103e-01 +-2.3723667478301933e+00 +-1.2771695557066784e+00 +6.7459578800971898e-01 +-2.3825870620519511e+00 +-1.1866561092311450e+00 +7.1001958973168000e-01 +-2.3734232364604111e+00 +-1.2278239500624990e+00 +7.4477200214632178e-01 +-2.3782458506681237e+00 +-1.1866091929186791e+00 +7.4542084078492254e-01 +-2.3774678340130104e+00 +1.6905145872977263e+00 +1.6082254648880087e-01 +-4.2340166714691509e+00 +-7.3853176184158464e-01 +1.9100926097072049e-01 +-2.6842549487898624e+00 +-1.0985903145498692e+00 +3.1586901355817670e-01 +-2.4156704815813548e+00 +-8.2045974804776922e-01 +4.1265412229953241e-01 +-2.9673001727199440e+00 +-7.2135034081945981e-01 +4.8175432104561750e-01 +-2.8440491675423107e+00 +-1.1492800438920390e+00 +4.2657869667455983e-01 +-2.3637346190929986e+00 +-7.7164111414495384e-01 +6.4382989926411593e-01 +-3.0669626939177648e+00 +-7.3343546257862069e-01 +5.9072217754173784e-01 +-2.8202038946734675e+00 +-1.2911720853420052e+00 +5.8960805731053600e-01 +-2.3969067900296004e+00 +-1.0358127464958100e+00 +5.9230223181611286e-01 +-2.3995314200451476e+00 +-1.1744041594592944e+00 +6.1223160529987530e-01 +-2.3696347617332667e+00 +-1.1390035428960530e+00 +6.7265349771093796e-01 +-2.3731587589148067e+00 +-1.3046667862863506e+00 +6.9781664605474070e-01 +-2.4021895417088488e+00 +-1.2969048385089155e+00 +6.8660729380793406e-01 +-2.3831812286518077e+00 +-1.0717993550785534e+00 +7.1384493940255755e-01 +-2.4467359735100200e+00 +-1.3060564741234142e+00 +7.1635023942060183e-01 +-2.4142047040576067e+00 +-1.2519231046170776e+00 +8.6001877251654824e-01 +-2.4173379496134544e+00 +-1.1430322542966107e+00 +3.3137144427856806e-02 +-2.4011874870538232e+00 +-1.1656400471035213e+00 +4.4547000925908561e-02 +-2.3731340339396789e+00 +1.4165793293014668e+00 +1.6879668384534402e-01 +-3.8264879269778711e+00 +1.8408402621005735e+00 +2.5358715202939247e-01 +-4.4167832167337551e+00 +-1.1256656309411752e+00 +1.7399925511169809e-01 +-2.3531611269992898e+00 +-9.3261057821216753e-01 +2.1237935804049732e-01 +-2.4613767238208184e+00 +-1.1009489645564061e+00 +2.1523977557268381e-01 +-2.3855075891348454e+00 +-1.1900817130562771e+00 +2.1688349139713223e-01 +-2.3733306234950113e+00 +-1.2098556542543553e+00 +2.1612832744739024e-01 +-2.3523826726350370e+00 +-1.1378275270453579e+00 +2.9873412289814977e-01 +-2.4095863838647280e+00 +-7.9147344669761754e-01 +4.4783696597208938e-01 +-2.5864268302093074e+00 +-1.1738943999593823e+00 +4.3972211728792832e-01 +-2.4157532031230229e+00 +-8.0295810345157970e-01 +5.5310618793223609e-01 +-2.5913019191650650e+00 +-9.8700649624228665e-01 +5.5179910039039337e-01 +-2.4274249222867699e+00 +-1.0699380946823305e+00 +5.5246713009415427e-01 +-2.4064948744206149e+00 +-1.3010247843731471e+00 +5.8203140951295151e-01 +-2.4078402576722544e+00 +-7.5249361137055049e-01 +6.4762543789789118e-01 +-2.7272548906445908e+00 +-1.1437664138174068e+00 +5.7570457505555539e-01 +-2.3903969432875596e+00 +-9.2851288387100028e-01 +6.1027382649273287e-01 +-2.4683720339185879e+00 +-1.0927470922022964e+00 +6.2387988958405483e-01 +-2.4403623642190917e+00 +-9.4771055715858687e-01 +6.3545297865058237e-01 +-2.4515650883608888e+00 +-1.2772206525582412e+00 +6.4447718049122416e-01 +-2.4074136032501197e+00 +-1.0397564625553803e+00 +9.6398616040197804e-01 +-3.3921344754093079e+00 +-1.3434268882555844e+00 +6.8697304123301384e-01 +-2.3981840345444865e+00 +-7.9550389703035917e-01 +7.7492209300276982e-01 +-2.6154270807901372e+00 +-1.2174445376367133e+00 +7.3034765145154013e-01 +-2.3805657845918278e+00 +-1.1311792551685254e+00 +8.9770660117076795e-01 +-2.6358067449711409e+00 +-1.1502222557219108e+00 +1.7597059532221886e-02 +-2.9399687754179125e+00 +-1.0168186955597049e+00 +2.3449060468511872e-02 +-2.4739383921647025e+00 +-1.1568414075204603e+00 +2.6344236931874935e-02 +-2.3728208220829581e+00 +-8.8942111649084132e-01 +8.3760431955000436e-02 +-2.4665514812128775e+00 +-1.1254536298152114e+00 +1.2799419222400751e-01 +-2.3717193200665920e+00 +-1.1409633760848448e+00 +1.2223123924892197e-01 +-2.3772029492518638e+00 +-1.1285280328842393e+00 +1.4781866088815324e-01 +-2.3794951249422009e+00 +-1.1302553330361484e+00 +1.5636289497366093e-01 +-2.3807606420036476e+00 +-1.2091371435938918e+00 +1.7621389415835456e-01 +-2.3655483363696970e+00 +-8.9487423636490993e-01 +1.8368202228755184e-01 +-2.4953636179752681e+00 +-1.0122404941640559e+00 +2.1327381233069032e-01 +-2.4177498405122813e+00 +-2.1494492381236672e+00 +3.5000889157012399e-01 +-3.7823977691420261e+00 +-1.1773879879980023e+00 +2.1939933074105594e-01 +-2.3999650344821615e+00 +-1.7159512912992652e+00 +2.7898699397319793e-01 +-2.9461478849110176e+00 +-1.2988885998869952e+00 +2.4155144010035590e-01 +-2.3663535998703242e+00 +-8.1609708126863467e-01 +2.7588580654444678e-01 +-2.5742462485738757e+00 +-9.2904493195228044e-01 +2.7903518779436293e-01 +-2.4704812849382396e+00 +-7.3908199057754442e-01 +3.0598758075063132e-01 +-2.7038443816747608e+00 +-1.0728693540850498e+00 +3.2345598982399953e-01 +-2.4029654289305249e+00 +-7.5231483379987385e-01 +3.8153174283524005e-01 +-2.7620712279169028e+00 +-8.9328282550569338e-01 +4.1473981728059289e-01 +-2.4739409858007892e+00 +-1.1427136061096270e+00 +4.1150741107733108e-01 +-2.3552751769539251e+00 +-1.1355803955846988e+00 +4.2455109480669212e-01 +-2.3868136704416107e+00 +-1.1051827385728612e+00 +4.2964712036506553e-01 +-2.3656181504766818e+00 +-1.1235452270372202e+00 +4.4459989610893424e-01 +-2.3838572481982556e+00 +-7.9726279979161996e-01 +4.7918839522607887e-01 +-2.5528534313108326e+00 +-9.4988652146691255e-01 +4.6689020973961332e-01 +-2.4619891548312522e+00 +-1.1175411881391848e+00 +4.5506981143961295e-01 +-2.3866309512472021e+00 +-1.4614232853343314e+00 +5.2606259312219883e-01 +-2.5958642712209126e+00 +-1.3029330364671456e+00 +6.2851625568495861e-01 +-2.5856866689851263e+00 +-1.1563608018953959e+00 +5.8784313036172287e-01 +-2.3942042276634221e+00 +-1.3581799341970184e+00 +6.0089842682926675e-01 +-2.3671736629241704e+00 +-1.3687031619377332e+00 +6.2370229210076711e-01 +-2.4248723745900600e+00 +-1.0526791855598681e+00 +6.9088198044617821e-01 +-2.4177608866206848e+00 +-1.4081265614074245e+00 +6.9112077257481752e-01 +-2.3660827419762120e+00 +-7.8253886075562462e-01 +8.3757517107081070e-01 +-2.9062181174363104e+00 +-8.0018969535242246e-01 +7.7071643620301267e-01 +-2.6105761755080534e+00 +-7.5925116217406641e-01 +8.8070391500410228e-01 +-2.9614392994201557e+00 +-1.2470760601793247e+00 +7.3045871886093405e-01 +-2.3811974630597894e+00 +-1.2386838081430207e+00 +7.3925759422679260e-01 +-2.4118304362559932e+00 +-1.1782556333092591e+00 +7.2977441097181950e-01 +-2.3776996079830193e+00 +-1.1995304845343577e+00 +7.3882914389160059e-01 +-2.4092607682010549e+00 +-1.1554109096535687e+00 +7.3473370801924465e-01 +-2.3958324785353176e+00 +-1.2613468952054847e+00 +7.4709767522194004e-01 +-2.4057419818526831e+00 +-1.2249486093750179e+00 +7.4428571829564960e-01 +-2.3967079188385476e+00 +-1.1989388451609062e+00 +7.3978615974894790e-01 +-2.3711861108081731e+00 +-1.2076665019916515e+00 +7.4684369404741335e-01 +-2.4023899552408312e+00 +-1.2251244400265069e+00 +7.4924689353396334e-01 +-2.4078750158997990e+00 +-1.1819500819105795e+00 +9.2884300838758027e-01 +-2.4336288270824462e+00 +-1.2095520695475013e+00 +1.0114491070414876e-01 +-2.3559698638387014e+00 +-1.1213717460928456e+00 +1.0822258262875364e-01 +-2.3792618767569862e+00 +1.2235306170076743e+00 +2.2384141442166047e-01 +-3.5538949813497398e+00 +-1.1255696976427911e+00 +1.6508816834899129e-01 +-2.3733847381266071e+00 +-1.1294498278920166e+00 +1.6540674774431974e-01 +-2.3806204651283016e+00 +-8.9282529894546458e-01 +1.7438217089327471e-01 +-2.4864843496465361e+00 +-1.5187980516855693e-01 +5.0907519084085244e-02 +-7.0649444197544542e-01 +-1.3737698937778724e+00 +2.0181292533750414e-01 +-2.3977963767847399e+00 +-1.1755591995453070e+00 +1.9856215730166885e-01 +-2.3669624472819168e+00 +-9.1805128741696218e-01 +2.1026070102464647e-01 +-2.5537415955610223e+00 +-1.3557140195214681e+00 +2.1302696726580642e-01 +-2.3981549311379990e+00 +-1.2342630355374260e+00 +2.1704585299190607e-01 +-2.3556212423199621e+00 +-1.2008115010727003e+00 +2.1897194562863953e-01 +-2.3640963657868275e+00 +-1.1502542926015862e+00 +2.2978780973138385e-01 +-2.3998867209900232e+00 +-1.2536360191530163e+00 +2.3113532615474036e-01 +-2.3716756963940462e+00 +-8.0833465436804175e-01 +2.5222175195963809e-01 +-2.5876359897573082e+00 +-8.0099227552889229e-01 +2.5204633628778095e-01 +-2.5833574350097357e+00 +-1.1832963088699668e+00 +2.8148042377439431e-01 +-2.3641920171183433e+00 +-1.2014957222760976e+00 +2.8273035737310082e-01 +-2.3639206134031685e+00 +-1.1789051204934178e+00 +2.8447957137103436e-01 +-2.3676039312806143e+00 +-1.2064245904278534e+00 +2.8946232112007247e-01 +-2.3979538543181143e+00 +-1.2398808674695228e+00 +2.8550058531650885e-01 +-2.3550600210209582e+00 +-1.3330137648414797e+00 +2.9932000434252004e-01 +-2.4055190873016645e+00 +-8.0859447775156124e-01 +3.1366424169227047e-01 +-2.5804709072225442e+00 +-1.3273802943151172e+00 +3.1514266887134168e-01 +-2.3928209621673546e+00 +-1.2168771991984273e+00 +3.1336216264871325e-01 +-2.3638857622591800e+00 +-1.0329353128926155e+00 +3.2285097122872469e-01 +-2.4192718963152688e+00 +-1.0975810989344450e+00 +3.1948802128348353e-01 +-2.3765440315848316e+00 +-7.9584970637722108e-01 +4.0989265449014606e-01 +-2.5732372590686565e+00 +-7.3868836454562281e-01 +4.9382904057396521e-01 +-2.9207771113432379e+00 +-1.3140895783351778e+00 +4.1274253457947124e-01 +-2.4135504059002386e+00 +-9.0301308395889746e-01 +4.2957177315605199e-01 +-2.4916668068960672e+00 +-7.7531298820512962e-01 +4.8524392406179079e-01 +-2.6185045458645084e+00 +-1.3165264075004439e+00 +5.0135296322700407e-01 +-2.4207459075171860e+00 +-1.3165264075004439e+00 +5.0135296322700407e-01 +-2.4207459075171860e+00 +-1.1952915597026681e+00 +5.0131747076056887e-01 +-2.3399560294124826e+00 +-7.0933588985362228e-01 +5.9548768113794304e-01 +-2.7258852625015968e+00 +-1.2311961110477319e+00 +5.8080036471490748e-01 +-2.3124522446504119e+00 +-1.2336346999769030e+00 +6.0192708816219409e-01 +-2.4183909476224352e+00 +-1.1771979003816069e+00 +5.9945736285997064e-01 +-2.3943864187782555e+00 +-1.3115407352110802e+00 +6.1804154430867031e-01 +-2.4202087813303441e+00 +-7.8063618447330274e-01 +7.2525714959392817e-01 +-2.7702731162696876e+00 +-1.0137972692796720e+00 +6.4646178435422308e-01 +-2.4064942169028907e+00 +-9.4559595427247922e-01 +8.7409202453656265e-01 +-3.0931406714188849e+00 +-8.4206969896723860e-01 +8.9960579422647136e-01 +-3.1139257054144749e+00 +-8.9942455837845225e-01 +8.6852237681664701e-01 +-2.9188915437207528e+00 +-1.1846055156164732e+00 +7.2858766362763061e-01 +-2.4014419246814334e+00 +-7.9197248102817797e-01 +7.9743001272852476e-01 +-2.6221669321459715e+00 +-1.1688677450205003e+00 +7.4210006228311487e-01 +-2.4019866148649869e+00 +-1.1683411699902979e+00 +7.4290943774250240e-01 +-2.4003164950712064e+00 +-1.1660545688865409e+00 +7.3293179164217448e-01 +-2.3659617072893622e+00 +-1.2214983812256897e+00 +7.8648578520760082e-01 +-2.4113086787836226e+00 +-1.2715804646576818e+00 +9.1902552981619379e-01 +-2.4676923545632481e+00 +-1.1718673999320859e+00 +9.2910923586323702e-01 +-2.4333048119277776e+00 +-8.5850471726570066e-01 +5.7074318290565335e-02 +-2.6199983361357821e+00 +-1.1623104919809715e+00 +6.5769011899271423e-02 +-2.3923078580165846e+00 +-1.1950272815480449e+00 +7.1915592947631307e-02 +-2.4019415298278388e+00 +1.3919189125672446e+00 +7.0944358348182010e-02 +-2.2911159487629185e+00 +-1.1787886309141933e+00 +9.2098050061855952e-02 +-2.3831474598540492e+00 +-1.2456032143379998e+00 +9.2472645109986748e-02 +-2.3631901903392345e+00 +-1.2093544187198324e+00 +9.2396739376521028e-02 +-2.3628901862101919e+00 +-1.2603835478409311e+00 +1.5409003659402509e-01 +-2.3742868733856306e+00 +-1.1580958841019104e+00 +1.7232955688323803e-01 +-2.4101220157728629e+00 +-1.1679168402382698e+00 +2.0378226678195394e-01 +-2.3818246085643233e+00 +-1.3907619518618437e+00 +2.0853558998618923e-01 +-2.3935460513159579e+00 +-1.2794154626872667e+00 +2.1031837710289611e-01 +-2.3954524899703697e+00 +-1.1573123437931958e+00 +2.4100654525742651e-01 +-2.4129108523529390e+00 +-7.5090404261451449e-01 +2.7002704617572437e-01 +-2.6935498755065410e+00 +4.6793964675411787e-01 +2.6150810283937176e-01 +-2.6375820005066268e+00 +-7.3089504790403059e-01 +2.7253758366552044e-01 +-2.7008195821574250e+00 +-7.9736807776890584e-01 +2.8563277456813274e-01 +-2.5854273191719161e+00 +-1.4011280399500430e+00 +2.9119640439848099e-01 +-2.4015506800635897e+00 +-7.6535141211266988e-01 +3.1448863938209187e-01 +-2.6463199836193652e+00 +-1.0507690836556971e+00 +3.1129634629007213e-01 +-2.4128729181388042e+00 +-6.9757556406422572e-01 +4.0815770193117779e-01 +-2.8179224642418692e+00 +-7.9840902319611251e-01 +3.8046259652021897e-01 +-2.5864921893885890e+00 +1.7729437575962017e+00 +5.0179146421016108e-01 +-3.1275080717904902e+00 +-1.1136721556229348e+00 +4.0334543977796294e-01 +-2.3831513776764535e+00 +-9.0030543205649016e-01 +4.2957755999346248e-01 +-2.5810576661537961e+00 +-1.3152107710857968e+00 +4.3386496427970267e-01 +-2.4193235174529684e+00 +-7.6919918915335228e-01 +4.9774772822498220e-01 +-2.8228473253401223e+00 +-1.1148535112397107e+00 +4.6604142882020239e-01 +-2.4357361129761630e+00 +-1.4300648662647446e+00 +4.7688722051903043e-01 +-2.3995077278289529e+00 +-1.2418471006178766e+00 +4.8853794769107295e-01 +-2.4093852358360714e+00 +-9.7962957840580545e-01 +4.9264366005136428e-01 +-2.4360350301369187e+00 +-1.4196994950352100e+00 +4.9617723893685561e-01 +-2.3978830197571241e+00 +-1.3955869893701522e+00 +4.9891065694489045e-01 +-2.3997284525481160e+00 +-9.5588870766560396e-01 +5.4077863653378822e-01 +-2.4177279817479738e+00 +-9.8614111086435485e-01 +5.4063307738878386e-01 +-2.3999782373143304e+00 +-1.2385001662363304e+00 +5.5626176334047739e-01 +-2.3886277253606489e+00 +-1.4160772335494864e+00 +6.0101615368724326e-01 +-2.4168053386304331e+00 +-8.1415413208538989e-01 +6.4477316961482589e-01 +-2.5871227577336691e+00 +-1.2173217909509835e+00 +6.1432754460545513e-01 +-2.3242587640898686e+00 +-1.1927968268578413e+00 +6.2648208907473724e-01 +-2.3417504933895139e+00 +-1.1783070098094919e+00 +6.6070933252161690e-01 +-2.4071025665085091e+00 +-1.0611561242396379e+00 +7.2762533239854665e-01 +-2.4494744723227719e+00 +-1.2121620989144264e+00 +7.3231514613852378e-01 +-2.4067076833445538e+00 +-1.1856942724951147e+00 +7.8750137970856893e-01 +-2.4673832503257525e+00 +-2.8054536090143323e+00 +2.6217512253017011e-01 +-5.9237107926809278e+00 +-1.1909776879811182e+00 +1.7720400690614424e-01 +-2.3732056506322867e+00 +-1.3408683977749620e+00 +2.0793775905723635e-01 +-2.3946767972626017e+00 +-1.2029452987251428e+00 +2.6655726759621384e-01 +-2.3690099895081058e+00 +-7.5974909962343606e-01 +3.0014786109877939e-01 +-2.6511657217785696e+00 +-1.1190940125619915e+00 +2.8522692432853858e-01 +-2.3813805140147544e+00 +-1.1959537334200798e+00 +2.8576187905067868e-01 +-2.3622814855070349e+00 +-1.2419655833135650e+00 +3.1367427162604700e-01 +-2.3645589382628511e+00 +-1.3673707068537297e+00 +3.3138324662006929e-01 +-2.4049118616371228e+00 +-7.5726307719378350e-01 +3.9961749602468599e-01 +-2.6512977322557596e+00 +-1.1173673959306869e+00 +3.7528716224721465e-01 +-2.3873871332526164e+00 +-1.2794696608524616e+00 +6.0673041343334111e-01 +-2.5884098226487025e+00 +-1.1285500120592327e+00 +5.8241376951843005e-01 +-2.3923220916508132e+00 +-9.6800238787380255e-01 +6.2972254468459532e-01 +-2.4401176369363498e+00 +-8.8466808544147479e-01 +5.9972312509705450e-01 +-2.3011709517728094e+00 +-9.5326259682450654e-01 +6.4972971541696878e-01 +-2.4664038374599659e+00 +-1.1561364041909408e+00 +6.3475104650416658e-01 +-2.3791082177975920e+00 +-1.0974645101938869e+00 +6.4028001364664600e-01 +-2.3749046939326028e+00 +-1.1847523033409988e+00 +6.5070206543475717e-01 +-2.3952838129426710e+00 +-1.1697584931634915e+00 +6.6801089603107033e-01 +-2.3943437861271462e+00 +-1.1530947243284237e+00 +6.8755735151545083e-01 +-2.2550745809487869e+00 +-1.2705537353672427e+00 +7.5272791365648795e-01 +-2.3958124764522446e+00 +-1.1501664131663747e+00 +2.6462466208177157e-02 +-2.3793829836978122e+00 +-1.3811803567985681e+00 +2.1242870856977725e-01 +-2.3901291627256964e+00 +1.4064244441045002e+00 +2.6005249142161263e-01 +-2.2978074815107226e+00 +-1.1396072705848037e+00 +3.1590410663397217e-01 +-2.3863643543154862e+00 +-1.1226849969320207e+00 +3.8597002726590307e-01 +-2.3778442860693709e+00 +-1.1155350637718859e+00 +4.3315056964723025e-01 +-2.3894846183218776e+00 +-1.1494511612802363e+00 +5.6044066473088239e-01 +-2.3862673135720955e+00 +-1.1525268280141847e+00 +5.6044032505912389e-01 +-2.3869662913873442e+00 +-9.0332187046261714e-01 +6.3536126635999879e-01 +-2.4782828087163065e+00 +-1.2992571496532239e+00 +6.3456172444453884e-01 +-2.3820776645600468e+00 +-1.0305864773843729e+00 +6.7244031901549373e-01 +-2.4254561628615292e+00 +-1.1188069778862904e+00 +6.8978753583830621e-01 +-2.3904048500960431e+00 +-1.1998622018138116e+00 +6.9275672617529238e-01 +-2.2760960741200531e+00 +-1.1301628549078866e+00 +6.9279196645417074e-01 +-2.2711168949228475e+00 +-1.1697968407633990e+00 +7.6030130566641840e-01 +-2.3934151984034386e+00 +1.3457412037804344e+00 +7.2557813557411158e-02 +-2.4422666959824642e+00 +4.1347596612989129e-01 +1.6797886209783758e-01 +-2.6334778744225522e+00 +1.4476358952296342e+00 +1.8442946278918629e-01 +-2.2660197326863276e+00 +1.3606275027949137e+00 +8.1793192171679407e-02 +-2.3354721488826589e+00 +1.4468544782423152e+00 +1.4874650539950299e-01 +-2.2469991189958431e+00 +8.5418222634824459e-01 +3.8032626455081558e-01 +-3.1421483723048107e+00 +1.4409904510669127e+00 +-7.0185726418345445e-02 +-2.2297972335777398e+00 +1.3933898503865090e+00 +-6.9847945510823406e-02 +-2.2710745596378934e+00 +1.4062949995473664e+00 +-6.9847150711951897e-02 +-2.2830977434321933e+00 +1.5187598417457537e+00 +1.6894542587397757e-01 +-2.8264924658522954e+00 +1.3912510663872986e+00 +1.5885697336729962e-01 +-2.3074494902282119e+00 +1.4249654558828453e+00 +1.9586692315747570e-01 +-2.2630598126924628e+00 +1.4063156743709102e+00 +2.0332001534219510e-01 +-2.2873120000113789e+00 +1.4065269299479679e+00 +2.6633428681752719e-01 +-2.3183397356944879e+00 +8.5565730919964733e-01 +3.8071322204413455e-01 +-3.1444808309580581e+00 +1.4488580479325364e+00 +-2.7512235911201294e-02 +-2.2180994493295318e+00 +1.4307274735093345e+00 +-2.7596672222188482e-02 +-2.2157719503947182e+00 +1.4519946870746867e+00 +-2.7531327739076079e-02 +-2.2340696273887448e+00 +1.6230293271097800e+00 +2.1399613420616907e-02 +-4.0099343198459012e+00 +1.3581466585479527e+00 +1.0630025770768189e-01 +-2.4216160260123401e+00 +1.4536532600176206e+00 +1.6622855944209247e-01 +-2.2454107549375188e+00 +1.3791411157956837e+00 +2.6911929130394135e-01 +-2.3107057260076020e+00 +1.4445956569555793e+00 +2.6913550614033716e-01 +-2.2583645614278574e+00 +9.2381657728375777e-01 +3.5923224660936309e-01 +-3.0958111411564748e+00 +1.4318311797581469e+00 +-7.6682191450439696e-02 +-2.6567019066550452e+00 +4.5222771356226561e+00 +-6.2147579097102598e-02 +-8.6427813279431867e+00 +3.9451782766106254e+00 +-4.0525521249843384e-02 +-7.6570292307238326e+00 +1.4713327316159728e+00 +6.5972334016416320e-02 +-2.2244853733511163e+00 +1.4025495263773371e+00 +9.7917472011703963e-02 +-2.2849670362202534e+00 +1.8618290515971967e+00 +2.9039194256790518e-01 +-4.3813589186148176e+00 +1.3520355989275423e+00 +1.3779275963285703e-01 +-2.4668827905923099e+00 +9.9726285794267899e-01 +3.8690523632526463e-01 +-3.3519063887702054e+00 +1.3836848421452592e+00 +2.7686090911151218e-01 +-2.3387789566517161e+00 +1.4658011718860611e+00 +2.8132416962571200e-01 +-2.2682999763543443e+00 +1.4613171215748861e+00 +2.8574706202594508e-01 +-2.2798495700328933e+00 +1.3445280405872746e+00 +-6.4149584157984163e-02 +-2.2809499644034190e+00 +1.3479165813614469e+00 +-1.2799258596732229e-02 +-2.4309258198805468e+00 +7.2515028943052484e-01 +5.7948228415922801e-02 +-2.8804333782063134e+00 +1.3562427583904386e+00 +5.6671284033845318e-02 +-2.3592330061074374e+00 +1.4387494955200371e+00 +7.0826792359069496e-02 +-2.2541186092738803e+00 +1.4163938778633860e+00 +7.3181567453635354e-02 +-2.2726391006439797e+00 +1.4387579320325559e+00 +2.3208126007491764e-01 +-2.6451398207560293e+00 +1.4165742954746172e+00 +1.8955638378495659e-01 +-2.2640599343584387e+00 +1.5771413778752843e+00 +2.2927865552725793e-01 +-2.2958682626660889e+00 +1.4644164659942356e+00 +2.8587022601593726e-01 +-2.2727954912268378e+00 +1.4318155036258733e+00 +2.8713642176519505e-01 +-2.2701477431734149e+00 +8.6290097357385309e-01 +3.8246170488551007e-01 +-3.1505740514601763e+00 +1.4347666294490327e+00 +2.9950647399881269e-01 +-2.2687962994334323e+00 +2.0520600501408226e+00 +4.9866214751829435e-01 +-2.9195279899044495e+00 +2.0466519593920398e+00 +5.0039457581460833e-01 +-2.9290508966647009e+00 +1.3808985507450571e+00 +-6.9698427197815452e-02 +-2.2012624541399735e+00 +1.3482285714392106e+00 +-6.1350668425385745e-02 +-2.2812835194767245e+00 +1.3854442855145033e+00 +-6.0446651097061210e-02 +-2.2058333818287061e+00 +7.2336617650623880e-01 +-3.6499769496769460e-02 +-2.8787912170172243e+00 +1.4173808326463566e+00 +-3.1177511974052882e-02 +-2.2128807308808676e+00 +1.4392502094500697e+00 +-1.9922006538418923e-02 +-2.2038744843827769e+00 +1.4111562709549632e+00 +-1.4680408443115318e-02 +-2.2263688941581097e+00 +6.1096983343144897e+00 +1.4694325425325105e-01 +-1.1287347218149533e+01 +1.4427377606701037e+00 +-1.0033665029697528e-02 +-2.2061592850184568e+00 +1.0741157527528697e+00 +3.2254639414851585e-02 +-3.2675202800049332e+00 +1.3496624064784681e+00 +1.9497473499906489e-02 +-2.4404411150449312e+00 +1.4276847538014472e+00 +6.0838813648627282e-02 +-2.6554700892975176e+00 +1.3417803533918242e+00 +7.1015482193175009e-02 +-2.4496958631576060e+00 +1.4338728483856642e+00 +6.8123228237458866e-02 +-2.2575839039793153e+00 +1.4172948882301448e+00 +7.0514126265837029e-02 +-2.2711668073374840e+00 +1.4101096898815866e+00 +7.0251621543935189e-02 +-2.2699606421808869e+00 +1.8627551273388117e+00 +2.9640325771385601e-01 +-4.3817039299798113e+00 +1.4015476891986824e+00 +1.8563468005748618e-01 +-2.6599276122411695e+00 +1.3955387051783923e+00 +1.5789223345022324e-01 +-2.3011605601799445e+00 +6.7830521936184462e-01 +1.9070400286512929e-01 +-2.8360387618789722e+00 +1.3480553184443169e+00 +2.0099045878172025e-01 +-2.4768407876445773e+00 +7.2572868471151297e-01 +2.5038393485397004e-01 +-2.8592857363057318e+00 +1.4279407313488912e+00 +2.5176542549932590e-01 +-2.2729842666716951e+00 +1.4086492334787741e+00 +2.5600216235857892e-01 +-2.2966278909408775e+00 +1.4184258879370573e+00 +2.5868067139176126e-01 +-2.3115446397715891e+00 +1.9174753807724987e+00 +4.9929889629912794e-01 +-3.0100463454671349e+00 +1.4167899184663848e+00 +-3.1475267336496811e-02 +-2.2073146446440766e+00 +1.4226794833500787e+00 +-1.8169453129095424e-02 +-2.2193605094100004e+00 +1.4715356459227447e+00 +-1.1598753995038824e-02 +-2.2108551070714864e+00 +1.4534467157668518e+00 +-9.6104805439270052e-03 +-2.2009847131408100e+00 +1.4561182470402358e+00 +-7.9854464273128520e-03 +-2.2000554517323185e+00 +9.2481158202272862e-01 +3.5765045621300201e-02 +-3.0867177940002026e+00 +1.5573930043597550e+00 +1.5265582112404399e-01 +-3.9514170275325902e+00 +1.4336581191606286e+00 +7.0589813817740918e-02 +-2.2580419799984974e+00 +1.3939494998195037e+00 +7.2270917543738225e-02 +-2.2884765072013256e+00 +1.4410899712326655e+00 +7.4653748218570307e-02 +-2.2541120902763274e+00 +1.3828589955308734e+00 +8.1343187469946759e-02 +-2.3262440819714874e+00 +1.3588023510366394e+00 +8.3886492880557356e-02 +-2.3376535603515300e+00 +1.3900662728493824e+00 +9.4888640654520046e-02 +-2.2911601117725007e+00 +8.5991063137858181e-01 +1.3411674238450066e-01 +-3.0007039575812264e+00 +9.5621483922507067e-01 +1.6756828637695118e-01 +-3.1370291765268696e+00 +9.0865935790675167e-01 +1.6976700317448154e-01 +-3.0798750666592500e+00 +1.4001511832126505e+00 +1.6520855465856049e-01 +-2.2893295343175124e+00 +7.9616372583601502e-01 +2.1961634732104990e-01 +-2.9347843936049869e+00 +1.3565453951324475e+00 +2.2625558077614463e-01 +-2.4132330828836097e+00 +1.3638459397065017e+00 +2.5745597333310544e-01 +-2.5018432735621903e+00 +7.3034612923408171e-01 +2.6825261057197247e-01 +-2.8784009739964893e+00 +7.3231308639423764e-01 +2.8146626827024102e-01 +-2.8791350329454848e+00 +1.3707585360775838e+00 +2.6129478815321444e-01 +-2.3728363208477696e+00 +1.4224933357155150e+00 +2.6066106222374663e-01 +-2.3071373780710931e+00 +1.4024361881538456e+00 +2.5635575434933705e-01 +-2.2883370147764688e+00 +9.5526040947233348e-01 +3.6064630001461434e-01 +-3.1305731623850015e+00 +6.2067827176648349e-01 +2.7695842908462687e-01 +-2.7501571590342753e+00 +4.3621080071260430e+00 +-4.5151261468737595e-02 +-8.4287215945779455e+00 +1.4214192783469113e+00 +-2.9517104711105947e-02 +-2.2182523179308715e+00 +1.3855994598752339e+00 +-1.8547700686149558e-02 +-2.2579105022267423e+00 +1.3449544216213163e+00 +-1.5166349764460593e-02 +-2.4004045794576245e+00 +1.4743032922910209e+00 +4.2535754487010684e-02 +-3.8135020121634744e+00 +1.4769301833386668e+00 +4.4855102638118448e-02 +-3.8147919773949881e+00 +1.4769301833386668e+00 +4.4855102638118448e-02 +-3.8147919773949881e+00 +1.3505932495246793e+00 +2.2211383551038518e-02 +-2.4366323419157530e+00 +1.5789849577230788e+00 +8.2478572073711121e-02 +-3.9476281946176388e+00 +6.1354072593213482e-01 +4.4047387805219669e-02 +-2.7602812388916638e+00 +1.4337931029499997e+00 +6.8051341310895477e-02 +-2.6344979292202870e+00 +1.3429534780368839e+00 +6.8817161267854948e-02 +-2.4496486768480334e+00 +1.3432870015298679e+00 +6.9610360452606837e-02 +-2.3961916001651131e+00 +1.3920261578362265e+00 +7.0226523728616957e-02 +-2.2847277336746656e+00 +1.4375773177189954e+00 +7.1972691448317569e-02 +-2.2564144986996761e+00 +1.4334984770606660e+00 +7.2257170939713219e-02 +-2.2563829733390204e+00 +1.4077529837899225e+00 +7.8059257816204777e-02 +-2.2780913009403236e+00 +1.8136808884151698e+00 +2.2319276469779678e-01 +-4.4039868822038475e+00 +1.3778160301819284e+00 +9.5055314376196645e-02 +-2.3075858621489416e+00 +1.8637330080711647e+00 +2.8781647699597579e-01 +-4.3759321953464614e+00 +1.8635895265745381e+00 +2.8841326603018896e-01 +-4.3819547753660526e+00 +1.8650027180216302e+00 +2.9209491050673420e-01 +-4.3798124930363080e+00 +1.8650027180216302e+00 +2.9209491050673420e-01 +-4.3798124930363080e+00 +1.5190501628309032e+00 +1.9726899957760219e-01 +-2.8405995221256997e+00 +1.3425121686431789e+00 +1.5943017979034818e-01 +-2.4588065964115207e+00 +1.3621576248421714e+00 +1.6074956420440462e-01 +-2.3690210087342871e+00 +1.3868836649042899e+00 +1.5826888610087017e-01 +-2.3089162750710845e+00 +1.7803727638068827e+00 +3.8997224352053944e-01 +-4.4322484871915213e+00 +1.3991695117424978e+00 +1.6527722763951486e-01 +-2.3043145864098644e+00 +1.4556275679452937e+00 +1.6397231163477768e-01 +-2.2328524985619893e+00 +1.4291897437760455e+00 +2.4738191183306132e-01 +-2.6553857143254049e+00 +9.5511952871840144e-01 +2.7726537576670668e-01 +-3.1296435915928646e+00 +1.4419448886816260e+00 +2.1214962463109729e-01 +-2.2846679937394412e+00 +1.3563072400660294e+00 +2.2773638423070944e-01 +-2.4120023958877517e+00 +8.0270725159252920e-01 +2.7202399553326911e-01 +-2.9300896101463803e+00 +1.3569580918568129e+00 +2.5705702405760056e-01 +-2.4158772394370285e+00 +1.3988248928783720e+00 +2.5201278013560008e-01 +-2.3278210617610982e+00 +1.4109250063292891e+00 +2.5191154328740262e-01 +-2.3163934129988055e+00 +2.1212115076793037e+00 +5.1709565387236700e-01 +-2.9757261155204073e+00 +1.4686703984661533e+00 +-4.1265194133173243e-03 +-2.2177492382744162e+00 +1.6351466762126079e+00 +1.2207957417435958e-01 +-4.0388802660322174e+00 +2.4301292154955618e+00 +1.9969019019951992e-01 +-4.2534701811081908e+00 +8.4258528846473468e-01 +9.8050026884573052e-02 +-2.9894348280025214e+00 +1.8296587871350680e+00 +2.1760745305565823e-01 +-4.3963568803777964e+00 +1.8462145905999490e+00 +2.6841099058765888e-01 +-4.3937569694768914e+00 +1.7965674194298809e+00 +2.6959162116486507e-01 +-4.4119692009607521e+00 +1.8387730282070611e+00 +2.7068615369653803e-01 +-4.3941453321637605e+00 +1.8498730137431183e+00 +2.7917750849569117e-01 +-4.3909956128428771e+00 +1.0659806994331678e+00 +1.7949097294558666e-01 +-3.2542229089374679e+00 +1.8338307648695622e+00 +3.4668296420451516e-01 +-4.4226196179881985e+00 +1.7901780701580470e+00 +3.9045047162640856e-01 +-4.4323699490538750e+00 +1.4367709557111228e+00 +1.5817691558659425e-01 +-2.2528844238846735e+00 +1.4102201948990616e+00 +1.6374186327352711e-01 +-2.2981316601093225e+00 +1.8091386250529844e+00 +4.2595753350526216e-01 +-4.5193064648547878e+00 +1.0098335194028447e+00 +2.5534504276768882e-01 +-3.1991414059345344e+00 +1.4254320584042337e+00 +1.8302963642111222e-01 +-2.2661874564871725e+00 +1.3805209391733513e+00 +2.4206724630635826e-01 +-2.5337141641426784e+00 +1.4029497280641290e+00 +2.5310541384006818e-01 +-2.2878890261344678e+00 +9.5832620490238618e-01 +3.6268692405786157e-01 +-3.1313222084834145e+00 +6.2085665496999176e-01 +3.1030615998887950e-01 +-2.7704113375004042e+00 +1.5371933383679588e+00 +1.7296318946558550e-01 +-2.7591949094144588e+00 +2.0160857657899545e+00 +4.2688493117062792e-01 +-3.1376928527780650e+00 +1.4537543257657406e+00 +3.0020258617957368e-01 +-2.5838702233588378e+00 +5.1026597719799427e-01 +1.4185628815180751e-01 +-2.7451943299677799e+00 +1.6968254428932583e+00 +2.0039820258435448e-01 +-3.0155366620122450e+00 +1.5389046812100879e+00 +2.1006017640718436e-01 +-2.7848493097451916e+00 +1.4200506010798650e+00 +2.8896986310078093e-01 +-2.6008041580065711e+00 +3.6844166385359917e-01 +-5.7751890745375907e-02 +-2.6654022054737312e+00 +1.6318594798869017e+00 +6.2956458782689073e-02 +-2.9327312534402599e+00 +1.9901001100155047e+00 +1.5686036927169600e-01 +-3.4598977211704884e+00 +1.5966083085537048e+00 +1.6071099579317824e-01 +-2.8893810023841184e+00 +1.4953687522882222e+00 +1.6272163217510588e-01 +-2.6868046655070654e+00 +4.6389871438158875e-01 +1.7156282588395586e-01 +-2.8026226310177194e+00 +1.5097554561868263e+00 +2.6724441552894312e-01 +-2.7797212159057905e+00 +3.6065748026805944e-01 +4.0465498367315944e-01 +-2.7040464276307734e+00 +5.7370945858068212e-01 +4.7334045983307377e-01 +-2.7954589387781765e+00 +3.8407928593600377e-01 +-4.0507550003849438e-02 +-2.6895331477202160e+00 +1.8499363954967787e+00 +2.3144788105856287e-01 +-3.2719208372996951e+00 +1.6370534901476614e+00 +2.3796837354878900e-01 +-2.9522833206835863e+00 +1.4658391343616497e+00 +2.3432918638989911e-01 +-2.6324336898607927e+00 +1.6852836044016108e+00 +2.6139662668491931e-01 +-3.0329807524235655e+00 +2.7080336518104281e-01 +3.4734166526800059e-01 +-2.6810449550328648e+00 +-4.2223309816747306e-01 +-1.2309076223369327e-02 +-6.4383313704680489e-01 +3.6054617042069731e-01 +-4.6187827165971397e-02 +-2.6297981664149819e+00 +4.8589356219679114e-01 +4.8962396377604682e-02 +-2.7573661068675936e+00 +1.5632789392764084e+00 +8.2093656562188394e-02 +-2.8376052069404976e+00 +1.8607199122069427e+00 +1.2937266007421455e-01 +-3.2783704041491943e+00 +1.6509773801345053e+00 +1.3934587073440705e-01 +-2.9766906590736202e+00 +1.4620518165501479e+00 +1.5149048489048589e-01 +-2.6371703830739399e+00 +1.4200109401394883e+00 +1.7252817784663160e-01 +-2.5474315747558642e+00 +1.5372243021772491e+00 +1.7754910340247379e-01 +-2.7953886531902228e+00 +1.4697053040523960e+00 +2.4812476600878194e-01 +-2.6388254383164562e+00 +1.5627525302789147e+00 +3.0696914905283090e-01 +-2.8401200424221442e+00 +1.9451675383837943e+00 +4.2759537778354989e-01 +-3.0156363049333361e+00 +1.9042167109386361e+00 +5.2036430783281729e-01 +-3.1071881126978176e+00 +3.7492198895719675e-01 +4.4238995168506162e-01 +-2.7037069556566160e+00 +-4.4006313043254636e-01 +4.7883103599981325e-02 +-6.4558865155542489e-01 +8.0203294529762992e-01 +-6.7773399411620319e-02 +-2.9488825196299966e+00 +4.2810447985228695e-01 +3.7134057268248560e-02 +-2.7321031260085111e+00 +1.5531748495779019e+00 +1.9743446448651147e-01 +-2.8345726945132395e+00 +1.7076356221366948e+00 +2.2983063840968659e-01 +-3.0557114011048458e+00 +1.5320192791221954e+00 +3.1452847428315978e-01 +-2.7885615220503222e+00 +1.8926510489120290e+00 +3.6905625637754763e-01 +-3.1048439356684252e+00 +1.7087696904538570e+00 +3.6205571230399186e-01 +-2.8282331127299232e+00 +4.3393590443562835e-01 +3.3991638622317710e-01 +-2.7557099291159282e+00 +1.9030158664017545e+00 +4.3598369738483406e-01 +-3.0419840325156180e+00 +2.0365582488103784e+00 +4.7382371949020113e-01 +-3.0831860132811819e+00 +1.9041371425491433e+00 +5.0335941511463411e-01 +-3.3107883422089195e+00 +1.5442231191442701e-01 +4.2180231898388926e-01 +-2.7320130030492531e+00 +-4.4395792466409850e-01 +-6.8620818034768050e-03 +-6.3029330196539768e-01 +-3.3028233807547341e-01 +3.6327419491084360e-03 +-7.0291763655421569e-01 +4.4187885672292926e-01 +-5.7781156292941678e-02 +-2.7197946043561254e+00 +4.0507142090478970e-01 +2.5599293893101161e-02 +-2.8069288368700422e+00 +1.4406247090263564e+00 +6.7386463077457395e-02 +-2.6071159363706347e+00 +1.7540230401117991e+00 +6.2847175874814185e-02 +-3.1243847952879227e+00 +1.4126236528946270e+00 +7.6472970575066274e-02 +-2.5169426165474968e+00 +1.6293022711512517e+00 +8.3779447072735144e-02 +-2.9411483519783586e+00 +1.6293022711512517e+00 +8.3779447072735144e-02 +-2.9411483519783586e+00 +1.4188636322038173e+00 +1.3506201635782322e-01 +-2.4951248823007557e+00 +1.5201895943273531e+00 +1.4809523539333699e-01 +-2.7823757264421687e+00 +1.6219341213231575e+00 +1.9395552697449750e-01 +-2.9311173206044918e+00 +1.3953525861652738e+00 +1.9218022090071535e-01 +-2.4308725680593377e+00 +1.7466039609955237e+00 +2.5032761208566473e-01 +-3.1120749457185668e+00 +1.4334910474723868e+00 +2.3820270863867221e-01 +-2.5720438028948331e+00 +1.6313606762705657e+00 +2.5772531786822173e-01 +-2.9287072682975972e+00 +1.5313161778351314e+00 +2.6739644298244430e-01 +-2.7406130818236125e+00 +1.4714073278229796e+00 +2.6852239524510602e-01 +-2.6570423839341508e+00 +1.4276713054055563e+00 +2.7255871970040607e-01 +-2.5470159109574313e+00 +6.3351788202739856e-01 +3.0356636080863747e-01 +-2.7930873576596054e+00 +9.5676517935884198e-01 +3.6478547806247774e-01 +-3.1390660487928321e+00 +1.7114713002951700e+00 +3.8149985891655908e-01 +-2.8336221356800206e+00 +1.8330669073208674e+00 +4.4839715767835092e-01 +-3.2424810296895852e+00 +3.1756971490263763e-01 +3.6214298552458990e-01 +-2.6508714365711352e+00 +1.8741712280419869e+00 +4.7971453520071300e-01 +-3.2815520330777477e+00 +2.0326799831700533e+00 +4.7702264843058417e-01 +-3.1216456134781994e+00 +1.8431756862201121e-01 +3.8245007996648800e-01 +-2.6921456325586051e+00 +3.5921807907015485e-01 +4.3902574804578520e-01 +-2.7066739881744564e+00 +1.8949744065701244e+00 +5.4055042542784337e-01 +-3.0955925447388366e+00 +-4.8343313964596080e-01 +-6.7862799436273092e-03 +-6.2962949487605224e-01 +-4.4784603806999040e-01 +-7.8077149484761287e-03 +-6.2952670514533793e-01 +-3.7994474111761295e-01 +-5.4738665506261427e-03 +-6.4058972734703468e-01 +-3.8286550725205065e-01 +-2.9942000236699382e-03 +-6.4938484266976026e-01 +-1.1247219576984059e-01 +-3.4758232031542567e-02 +-1.1562982040439718e+00 +-1.0488516177679648e-01 +-1.1996987760901008e-02 +-1.1297516194632284e+00 +1.4587674926550362e+00 +6.1829081489470417e-02 +-2.6348993196729742e+00 +1.4587674926550362e+00 +6.1829081489470417e-02 +-2.6348993196729742e+00 +1.8333612360930176e+00 +5.9222106058620751e-02 +-3.2332839066785519e+00 +1.9616016323998327e+00 +1.2549381496267378e-01 +-3.4151073050170093e+00 +1.9616016323998327e+00 +1.2549381496267378e-01 +-3.4151073050170093e+00 +1.5808208187713870e+00 +1.4559850782746878e-01 +-2.8692277585030350e+00 +1.6476102488790707e+00 +1.8946600559888679e-01 +-2.9800564218788463e+00 +1.4483238449374640e+00 +1.8463956901514816e-01 +-2.6255906475023396e+00 +1.4001773957089652e+00 +1.8773296482378135e-01 +-2.4505959966267810e+00 +1.7589667851580006e+00 +2.4386743754717843e-01 +-3.1266430136227576e+00 +1.5133492334606351e+00 +2.7683434325259737e-01 +-2.7636596350417717e+00 +3.4832569901274540e-01 +4.4190697547690244e-01 +-2.6817637963057197e+00 +-4.5628286754472797e-01 +4.9674183540544960e-02 +-6.6094900008249591e-01 +-4.3959286946184895e-01 +5.2355326203349623e-02 +-6.4442395320592250e-01 +-1.3704828575636449e-01 +3.1960478911319076e-02 +-1.0972603690452045e+00 +-4.4684902063299009e-01 +5.6372945190299360e-02 +-6.4909736911451543e-01 +-4.4684902063299009e-01 +5.6372945190299360e-02 +-6.4909736911451543e-01 +3.3267150123911182e-01 +-1.9238333320048939e-02 +-2.6140943700059514e+00 +-4.4319209633700563e-01 +5.9892549260138442e-02 +-6.5401365155985292e-01 +1.3285642867988905e+00 +-2.0843689385309463e-02 +-2.3621881976808163e+00 +1.0001658085854352e+00 +1.8332417431509207e-02 +-3.1775319115350067e+00 +6.2363585902933982e-01 +3.4196044936967943e-02 +-2.7796435895743414e+00 +6.0823986086607817e-01 +7.6261956702148775e-02 +-2.7685826765812500e+00 +1.4458172332729986e+00 +1.0626979074135123e-01 +-2.6047837340028059e+00 +6.2580459619616891e-01 +1.1231609250505399e-01 +-2.7870554858920067e+00 +1.0649874794774543e+00 +1.2865668095260438e-01 +-3.2447946665280574e+00 +1.7105040061739494e+00 +1.3246205843659023e-01 +-3.0627117088607139e+00 +1.4134790379498647e+00 +1.3341055080649628e-01 +-2.5016708351024830e+00 +1.3365696372133484e+00 +1.6492854310898403e-01 +-2.3524227121639623e+00 +8.1831690453145456e-01 +1.7169050462651350e-01 +-2.9660020970241203e+00 +1.4657924983657169e+00 +1.7275871822541400e-01 +-2.6424531942519520e+00 +8.6892007276798022e-01 +1.9091059519380854e-01 +-3.1230112666545300e+00 +1.4017573271432653e+00 +1.8999110197200345e-01 +-2.5224474780138508e+00 +1.5159536396371645e+00 +2.0017888797294675e-01 +-2.7778088842232380e+00 +1.4804783251184370e+00 +2.0848045203740914e-01 +-2.6644809381195529e+00 +7.9148352630687857e-01 +2.1258361818773280e-01 +-2.9441465321116613e+00 +6.4620984294818473e-01 +2.3117802717338479e-01 +-2.8097585786301216e+00 +1.5313064075339873e+00 +2.5559927968024559e-01 +-2.7389282646981172e+00 +1.5158307117385621e+00 +2.7137343577783862e-01 +-2.7491299282999080e+00 +6.6265808387477632e-01 +2.5990232092694437e-01 +-2.8136266318516805e+00 +1.5383692965037892e+00 +2.9060944436798969e-01 +-2.8000243303229690e+00 +1.6327693598019648e+00 +3.0200808771384297e-01 +-2.9311771691043198e+00 +9.0823411029067780e-01 +3.1696047754575807e-01 +-3.0924528852416082e+00 +1.8920793083545451e+00 +4.3051072300284104e-01 +-3.0389677960369550e+00 +3.4421968888131982e-01 +4.4407055582891447e-01 +-2.7369939558940288e+00 +-4.4732651458617417e-01 +-3.4722597097264188e-03 +-6.3039361631878033e-01 +-1.1128596981549185e-01 +-3.2746674477398006e-02 +-1.1573146869600957e+00 +6.0406480271488483e-01 +-4.5651110777915817e-02 +-2.7622587287988258e+00 +-4.4558017091924762e-01 +5.5239987760668061e-02 +-6.4942429459369644e-01 +-1.0194755275933079e-01 +3.0799621613406429e-02 +-1.1466566721547475e+00 +6.2024522702806173e-01 +-2.4288681591712637e-02 +-2.8139833398069531e+00 +1.6403103969806969e+00 +1.2788404886438688e-02 +-4.0236324683214395e+00 +2.0127603134520702e+00 +2.5552998251821439e-02 +-3.4822110004612425e+00 +1.5829376002085502e+00 +4.5034524546671020e-02 +-3.9543414583993521e+00 +1.4132026632623642e+00 +6.2524541978324133e-02 +-2.5263927840885843e+00 +1.3902027161447723e+00 +6.6270398104259470e-02 +-2.3935348679602040e+00 +1.7089702190611074e+00 +1.5163771532967435e-01 +-3.0606188979948281e+00 +6.1646876854668164e-01 +1.4898348471740536e-01 +-2.7777449197231929e+00 +5.9608089700015221e-01 +1.5365951068124256e-01 +-2.7594240302380655e+00 +1.8767138297879735e+00 +1.6487920388971644e-01 +-3.3116290948640339e+00 +1.4117429495345468e+00 +1.5886781109155873e-01 +-2.5074826804168353e+00 +7.3812903307036348e-01 +1.8873032437347820e-01 +-2.9036558920679769e+00 +1.4393843177221133e+00 +2.0949737786391662e-01 +-2.5851935595477027e+00 +1.6927062744700527e+00 +2.4130472661623537e-01 +-3.0299913811875570e+00 +7.4195342151969124e-01 +2.4399913909054369e-01 +-2.9012400016621229e+00 +7.1164708790101328e-01 +2.5551655187302463e-01 +-2.8542141551468534e+00 +1.3403945664524830e+00 +2.5660979069902912e-01 +-2.3419673419367495e+00 +5.1903903124578965e-01 +2.6855987499289519e-01 +-2.7508409631738511e+00 +5.1903903124578965e-01 +2.6855987499289519e-01 +-2.7508409631738511e+00 +1.6049398806746782e+00 +3.0348198757120259e-01 +-2.8945254312467408e+00 +6.9585067177835092e-01 +3.0432276664683189e-01 +-2.8618428177944710e+00 +1.7022632645246496e+00 +3.6103622079729142e-01 +-2.8073928611202557e+00 +1.0163712937717089e+00 +3.6674821393285750e-01 +-3.3500884759746525e+00 +1.7034411357084356e+00 +3.6583669866971569e-01 +-2.8057269190747549e+00 +2.0134466092046948e+00 +4.3154902138097406e-01 +-3.1052137736789667e+00 +2.0465219190868020e+00 +5.5362566188093387e-01 +-3.2006503176050103e+00 +6.9106319148041262e-01 +-4.7623806966550414e-02 +-2.8450966978931329e+00 +-1.3872940783949811e-01 +3.3725385833031071e-02 +-1.1001779984171085e+00 +6.6728228874893203e-01 +-4.0384152976588851e-02 +-2.8153487417402641e+00 +6.1884030000945833e-01 +-2.1571755225916020e-02 +-2.7780278965985037e+00 +8.1256071034474797e-01 +2.1069637678638464e-02 +-2.4342736581666942e+00 +8.5140311898395216e-01 +4.6846490707470163e-02 +-3.0066892256089637e+00 +7.5637441548782347e-01 +7.0238652097817392e-02 +-2.9050752863089184e+00 +1.3945941298813920e+00 +6.8839844299458122e-02 +-2.3952941583918759e+00 +1.5384373562441065e+00 +7.7252871226732092e-02 +-3.9095392706243897e+00 +1.0116585862303318e+00 +1.2787693271543296e-01 +-3.1950186995877292e+00 +1.6971789639944324e+00 +1.5091795766780328e-01 +-3.0421454714173848e+00 +9.9563920863851435e-02 +1.4677708818837512e-01 +-1.6865013583545254e+00 +1.6585347205438905e+00 +2.0004421520942384e-01 +-2.9874083229786299e+00 +1.4457239888759152e+00 +2.1599866246100968e-01 +-2.5944175728117633e+00 +7.9142528556706837e-01 +2.2880717327692532e-01 +-2.9433894986724827e+00 +7.7922342780125065e-01 +2.2971464895324542e-01 +-2.9328941657881065e+00 +6.5635723410675284e-01 +2.3500387348471174e-01 +-2.8186806605131483e+00 +5.7731251363332414e-01 +2.3769937449170869e-01 +-2.7388125405321300e+00 +7.5684263318062706e-01 +2.5048419277172296e-01 +-2.8983473548228114e+00 +7.9274102859828177e-01 +2.6632093217222519e-01 +-2.9464239855345005e+00 +7.4592487380391259e-01 +2.6548078264112357e-01 +-2.9012017199138906e+00 +7.8546575560103105e-01 +2.7104839748646464e-01 +-2.9424568256373678e+00 +7.1308804699669337e-01 +2.7379098907378280e-01 +-2.8726308900162825e+00 +6.2866807808310665e-01 +2.7974642899329066e-01 +-2.7730564523924355e+00 +1.6947418957763642e+00 +3.6205042159937872e-01 +-2.8353474184785643e+00 +1.6978627362311389e+00 +3.6154148864139862e-01 +-2.8173536997212465e+00 +1.7020633404329635e+00 +3.6192208955473942e-01 +-2.8112147095935014e+00 +1.7020633404329635e+00 +3.6192208955473942e-01 +-2.8112147095935014e+00 +1.5691710242660333e+00 +3.6591306371085153e-01 +-2.5882545224156015e+00 +1.5702088202715025e+00 +3.6642836388321942e-01 +-2.5958252768664636e+00 +2.0595685738573275e+00 +5.4752057279709143e-01 +-3.2122480607373167e+00 +1.3788424804372426e+00 +1.2561855306042061e-01 +-2.5692715314980163e+00 +1.3164304430994691e+00 +2.0624828123776226e-01 +-2.4433957250972225e+00 +1.8860381254048304e+00 +2.5131650452055232e-01 +-4.4633997094612896e+00 +1.8957388341385384e+00 +-6.2455098948962881e-02 +-3.4834616671935672e+00 +1.9408946601231869e+00 +-4.6252282994269263e-02 +-3.5119940078876581e+00 +1.3383360479817865e+00 +1.3798246974282963e-01 +-2.3479292976119397e+00 +8.6764962498813769e-01 +2.1053733032985961e-01 +-3.0285433032950397e+00 +5.2775363643361817e-01 +1.6928946858057925e-01 +-2.6840136134107828e+00 +7.0932171041897452e-01 +-6.3811060552425067e-02 +-2.8409906927119506e+00 +1.8907679145611440e+00 +7.2601575763105511e-02 +-3.4407498851958955e+00 +1.9249221520748727e+00 +7.4718004364723783e-02 +-3.4800239392740262e+00 +5.6349398013867025e-01 +2.4643243075924001e-01 +-2.7294263030369730e+00 +4.8050800885760721e+00 +-4.1041390805268890e-02 +-8.8890264665987608e+00 +6.4322075931627043e-01 +-4.3734508360279173e-02 +-2.7861267791681676e+00 +4.5353026839652930e+00 +-2.8939625873207954e-02 +-8.5717160928658593e+00 +1.8761220686895816e+00 +-3.9545290414593155e-02 +-3.4203638839420574e+00 +1.8993539094674672e+00 +8.8569850676861434e-02 +-3.4360075172078286e+00 +1.3187672758276465e+00 +5.7208055038802649e-02 +-2.3714526530897180e+00 +9.2461035302186423e-01 +1.9655799732791288e-01 +-3.0860065289252328e+00 +9.2643418930149479e-01 +1.9699903558101586e-01 +-3.0891778386206132e+00 +1.3236199184688877e+00 +1.5924451973712553e-01 +-2.3808293689065918e+00 +1.3259124909483071e+00 +2.2380027344548573e-01 +-2.4575209471768655e+00 +6.7960013225088722e-01 +-5.9644342326246755e-02 +-2.8180828575453609e+00 +1.5190559336928202e+00 +3.9442159875570329e-02 +-3.8770021996293127e+00 +2.4364995952901340e+00 +9.6783555190466664e-02 +-4.2030087431675867e+00 +1.3167028451847309e+00 +6.1139983954016999e-02 +-2.3640518297070661e+00 +5.9513447670894526e-01 +2.1176518819058984e-01 +-2.7469390132513034e+00 +1.8319638888139129e+00 +5.0199122129971530e-01 +-3.0583410699491211e+00 +1.5914233615984865e+00 +-5.5379612807588706e-02 +-3.9697487516588876e+00 +4.0171413806085923e+00 +8.1548248249524764e-05 +-7.7604390804805519e+00 +7.1788370846216587e-01 +-3.7845268055512610e-02 +-2.8736317385193035e+00 +1.0141696090267859e+01 +6.9250504332842733e-01 +-1.5822853683129797e+01 +5.9022812536428682e-01 +3.3356329326763197e-02 +-2.7391270332353392e+00 +1.9084631716203759e+00 +1.0892103869355751e-01 +-3.4330555075613232e+00 +1.3199358761326627e+00 +6.8792866775578082e-02 +-2.3643666274893889e+00 +2.4243946350747709e+00 +2.6751683413571403e-01 +-4.0390635711278939e+00 +1.5191188102783673e+00 +2.1834263773834969e-01 +-2.8324068571506826e+00 +7.9488818833615660e-01 +1.9100664246640300e-01 +-2.9386376472999229e+00 +6.1959542534470191e-01 +2.2418768652363491e-01 +-2.7730738087111244e+00 +6.3666390326680311e-01 +-9.6109554159157007e-02 +-2.7825092606162753e+00 +1.8177363130124617e+00 +-1.0222076147676583e-01 +-3.3469702928691940e+00 +6.7562177587795935e-01 +-5.5553517863860216e-02 +-2.8222128812244902e+00 +3.9366741438072355e+00 +-4.0405117244230120e-02 +-7.6323058287423642e+00 +4.6007951720961353e+00 +3.1864309171669041e-03 +-8.6676192865763237e+00 +1.6545397440235052e+00 +-2.0110560561213292e-03 +-4.0591653545954429e+00 +1.7503012217980560e+00 +1.7535040219051827e-02 +-3.1929572478845700e+00 +8.3868040029438895e-01 +1.4183577663596212e-02 +-2.9859002555792542e+00 +1.0833229965464024e+00 +9.2696422837832915e-02 +-3.2763845838859540e+00 +1.5743034721261004e+00 +1.6873230076579809e-01 +-3.9912989395919576e+00 +1.8096007052468102e+00 +2.1819347860440674e-01 +-3.2546675889851917e+00 +9.0840842479151440e-01 +2.1043835411985937e-01 +-3.0786380791674954e+00 +1.3166937872742273e+00 +1.9817211389686418e-01 +-2.4401436799556002e+00 +6.5147913248653277e-01 +-9.8417318528987247e-02 +-2.7934862897759611e+00 +6.5147913248653277e-01 +-9.8417318528987247e-02 +-2.7934862897759611e+00 +6.4615963843577851e-01 +-9.6056296103801245e-02 +-2.7896945925595737e+00 +6.4615963843577851e-01 +-9.6056296103801245e-02 +-2.7896945925595737e+00 +6.5357631994713905e-01 +-4.6318280948120967e-02 +-2.7938778723954703e+00 +6.5804990336016045e-01 +-4.5595329515323031e-02 +-2.7986139552559246e+00 +1.9517207723453134e+00 +-4.1567358598690290e-02 +-3.5266905102937840e+00 +6.4032743475227749e-01 +-3.5558674504225389e-02 +-2.7830803823037824e+00 +5.9217416031777947e-01 +-3.3756332213903395e-02 +-2.7413781836333939e+00 +1.4904838778024190e+00 +4.8544580341862133e-02 +-3.8332562111734205e+00 +9.8247434486765495e-01 +3.8526198851476477e-02 +-3.1570593276657397e+00 +1.3143165829343475e+00 +1.9886755624914158e-02 +-2.4000284943324379e+00 +1.0769688406467439e+00 +9.4776733021766466e-02 +-3.2687644771706617e+00 +1.8286067968611572e+00 +1.1819919617188239e-01 +-3.2894270299090973e+00 +1.3259983708727410e+00 +6.4503666894248732e-02 +-2.3451711552665593e+00 +6.1524371940274025e-01 +1.0318731380162864e-01 +-2.7633598532234527e+00 +1.8655713801409797e+00 +3.1245187478307263e-01 +-4.4467558188769605e+00 +6.8095223593717891e-01 +1.2153847682388574e-01 +-2.8321614049662895e+00 +1.0144912051569974e+00 +1.7578905370995884e-01 +-3.2087345549577591e+00 +6.3877521181336183e-01 +1.2206639458274487e-01 +-2.7887892502719671e+00 +6.3845850910078206e-01 +1.2368788985491538e-01 +-2.7914311324508700e+00 +1.1721631229580844e+00 +2.0931672878325897e-01 +-3.4131417359493970e+00 +1.1721631229580844e+00 +2.0931672878325897e-01 +-3.4131417359493970e+00 +7.1982633783974859e-01 +1.9143853929243765e-01 +-2.8769868834443582e+00 +9.5653617974968874e-01 +2.6276834210551447e-01 +-3.1351513229934929e+00 +7.8547089583102947e-01 +2.4051954878935908e-01 +-2.9261090818438142e+00 +8.0053490641326053e-01 +2.6832362301837187e-01 +-2.9342025790963082e+00 +1.3289325309861166e+00 +2.5356548653753636e-01 +-2.3822007441926467e+00 +6.8463990159927524e-01 +3.0113014383651315e-01 +-2.8341696353386934e+00 +5.6375133868510663e-01 +2.7874496098034968e-01 +-2.6955049663417476e+00 +1.8861191114703930e+00 +5.4017519950970860e-01 +-3.1178445124779510e+00 +1.8464458717505605e+00 +5.6654079946903491e-01 +-3.1627948519801921e+00 +8.6966947196348732e-01 +2.5603994930247013e-02 +-3.0195871551866196e+00 +1.5064690494080506e+00 +6.8681530084575976e-02 +-3.8778446994510101e+00 +9.7745974184286610e-01 +3.7056868210178312e-02 +-3.1519578831144832e+00 +1.3403345937666329e+00 +9.3704129908018144e-02 +-3.6358833417872636e+00 +7.3002292237501754e-01 +6.3546260943713379e-02 +-2.8708025179333916e+00 +9.6361493583241720e-01 +1.6396645579197430e-01 +-3.1436670966872700e+00 +9.1060180280463798e-01 +1.7225780307895072e-01 +-3.0783739734583455e+00 +1.1917200773361198e+00 +2.2233323609384700e-01 +-3.4392505277775163e+00 +1.5160863166946703e+00 +2.1214760582367917e-01 +-2.8348856303475425e+00 +8.0180147335408591e-01 +2.7172429055073100e-01 +-2.9316871289223223e+00 +1.7957946330859642e+00 +4.3905606331713376e-01 +-3.1842790160988037e+00 +1.7957946330859642e+00 +4.3905606331713376e-01 +-3.1842790160988037e+00 +6.1368086435642100e-01 +2.7820306078188117e-01 +-2.7451567847354696e+00 +8.4131884072741425e-01 +4.0372247590415089e-01 +-3.1548678147600686e+00 +1.8822368562298049e+00 +5.3251774345288128e-01 +-3.1187621306384310e+00 +1.8894329233996505e+00 +5.7900894846071471e-01 +-3.2426787989036092e+00 +6.1339330820980287e-01 +-3.8993198938636044e-02 +-2.7589611930045939e+00 +1.8095234894778887e+00 +-1.8053189634169128e-02 +-3.3012487706628937e+00 +1.3265072334343568e+00 +-2.7251326712770842e-02 +-2.5553944931674537e+00 +1.5442211035680902e+00 +1.0066515885380008e-01 +-3.9268375111994005e+00 +1.0055040536791893e+00 +1.0801693902448992e-01 +-3.1950363630908449e+00 +2.4116105726966683e+00 +2.2240446831717639e-01 +-4.1473738489684253e+00 +1.8461780571535562e+00 +3.0080013378568593e-01 +-4.4598892967312533e+00 +1.8577615315898601e+00 +3.0847608180531277e-01 +-4.4471020917713764e+00 +1.8535764067125731e+00 +2.1573052500091994e-01 +-3.3229105154254701e+00 +6.4099451782852157e-01 +1.1689440185823111e-01 +-2.7837867237829981e+00 +1.3191052886311521e+00 +1.2568247603310354e-01 +-2.4096103650438585e+00 +1.8556716428878142e+00 +3.4241790434627745e-01 +-4.4732571948904010e+00 +9.2783846786115254e-01 +1.9115371607740603e-01 +-3.0833917406705726e+00 +9.5583236207014677e-01 +2.4972655405528613e-01 +-3.1394520971953113e+00 +1.9319898982034489e+00 +4.4759129181614965e-01 +-3.3780072397757945e+00 +8.4326857761702445e-01 +4.0518623723852010e-01 +-3.1534774043409590e+00 +-2.0580636197013122e+00 +5.2653411420693752e-01 +-1.3266746724815370e+00 +-1.4251073705814270e+00 +7.5663260085413164e-01 +-2.5967509120285759e+00 +-2.1227668074497923e+00 +5.0331237919735672e-01 +-9.0179811946004418e-01 +-1.1032857968564218e+00 +7.6545013492499259e-01 +-2.6361349944126986e+00 +-2.0493983013633952e+00 +4.8795712518876339e-01 +-1.1530914591454411e+00 +-2.1423058613452093e+00 +5.6153172522141737e-01 +-1.0375783329571762e+00 +-2.1423058613452093e+00 +5.6153172522141737e-01 +-1.0375783329571762e+00 +1.7136338176909891e+00 +3.5455832491000185e-02 +-4.2965167929386716e+00 +1.5411748853383167e+00 +5.9892066536944295e-02 +-4.0307260045085949e+00 +-1.0034479454910674e+00 +2.3708537813478386e-01 +-2.4316620295687468e+00 +-2.0277795226346100e+00 +4.0670148515170779e-01 +-1.3161171479517610e+00 +-2.0277795226346100e+00 +4.0670148515170779e-01 +-1.3161171479517610e+00 +-2.0321388358432073e+00 +4.0587508320002463e-01 +-1.2591163090246149e+00 +-2.0532913291073385e+00 +3.9117157913649686e-01 +-9.2695054135158672e-01 +-7.2221793272958357e-01 +5.5864528267733093e-01 +-2.7530448823099287e+00 +-9.2304396644548314e-01 +5.9291575638642036e-01 +-2.7535036592322308e+00 +-2.0703007734925301e+00 +5.0102105379614714e-01 +-1.2452918857953053e+00 +-2.0703007734925301e+00 +5.0102105379614714e-01 +-1.2452918857953053e+00 +-2.5900276982423991e+00 +7.9685424184064857e-01 +-2.8357957719050657e+00 +-2.3335868523694221e+00 +7.7214991207807249e-01 +-2.6562250892509587e+00 +-2.0844565947481275e+00 +5.7315024854124641e-01 +-1.2672575385510632e+00 +-2.0844565947481275e+00 +5.7315024854124641e-01 +-1.2672575385510632e+00 +-2.0926115885452132e+00 +5.5930364006248134e-01 +-1.1542039145432688e+00 +-2.1042824213016607e+00 +5.5026874439245821e-01 +-1.0492041104854568e+00 +-2.1376683554394802e+00 +5.4896194138102083e-01 +-9.7685282494680781e-01 +-2.8021003130052033e+00 +9.5893700537231474e-01 +-3.0720952591992146e+00 +-1.2109223060205587e+00 +9.4544945807194569e-01 +-2.8717839021658502e+00 +-7.1182897995775829e-01 +5.0952820981684277e-01 +-2.6963027886288535e+00 +-2.0426699275168683e+00 +4.5453529929688674e-01 +-1.2447057424425245e+00 +-1.3961236427221391e+00 +5.4824134514807521e-01 +-2.2885814760616907e+00 +-2.0471678360038363e+00 +4.9368786702556633e-01 +-1.2606548658909398e+00 +-2.0807497149656662e+00 +5.2914149284520662e-01 +-1.5147704197795675e+00 +-2.4528314257272488e+00 +7.2116131915845505e-01 +-2.6796191899296526e+00 +-2.0562233673523038e+00 +5.3125311263478936e-01 +-1.2286969101917107e+00 +-2.0966798992031666e+00 +6.1511467045737889e-01 +-1.2245429090210214e+00 +-1.1260504904753570e+00 +1.1821437903847236e-01 +-2.5297337796374926e+00 +-1.4167607442576151e+00 +1.3496542540098644e-01 +-2.4191343738089195e+00 +-9.6714083896300385e-01 +1.4578294256419091e-01 +-2.4397628440839507e+00 +-9.6714083896300385e-01 +1.4578294256419091e-01 +-2.4397628440839507e+00 +1.8169217797677306e+00 +1.3161172293093187e-01 +-4.4403098336342417e+00 +-1.2504423262483824e+00 +4.1760151663356104e-01 +-3.9853418630002819e+00 +-2.1124452254152293e-01 +5.1604888168796814e-01 +-3.8057655695691999e+00 +-1.9847668692893106e+00 +4.0470862639809491e-01 +-1.3052763611529210e+00 +-9.8771746066311883e-01 +4.0300206018084989e-01 +-1.9894311599085561e+00 +-2.0225155162668913e+00 +4.3114642685494420e-01 +-1.2565199487026042e+00 +-2.0225155162668913e+00 +4.3114642685494420e-01 +-1.2565199487026042e+00 +-2.0656218273718765e+00 +4.2336671761681199e-01 +-1.0486843224311779e+00 +-9.3829985678930172e-01 +5.6634414734331373e-01 +-2.4696877513436255e+00 +-1.1046918279965006e+00 +5.8730466204714460e-01 +-2.6202555924046105e+00 +-2.0605255641282589e+00 +5.3246353363730758e-01 +-1.4429897101834772e+00 +-1.6895696683709258e+00 +6.4106022024813258e-01 +-2.4665382290591520e+00 +-2.5887378578353553e+00 +7.6012385746183930e-01 +-2.8083619119759922e+00 +-2.4878399121871135e+00 +7.2297523874245473e-01 +-2.6259329364583235e+00 +-8.8147288312167216e-01 +6.3784475464051160e-01 +-2.4861361968810822e+00 +-8.7855522080312010e-01 +6.5115160846860187e-01 +-2.5020265750073949e+00 +-9.6659161572793406e-01 +6.6087216985749442e-01 +-2.4914463391437942e+00 +-1.0188061916924718e+00 +7.0607542357386033e-01 +-2.7633614073914146e+00 +-2.0571515088670904e+00 +5.7651153824660939e-01 +-1.2756646875230560e+00 +-2.1847766708939371e+00 +5.4207163514143497e-01 +-8.5746492764011584e-01 +-2.1847766708939371e+00 +5.4207163514143497e-01 +-8.5746492764011584e-01 +-2.2338609656302042e+00 +5.7404925288469799e-01 +-9.0876612377414645e-01 +-8.8022284916628246e-01 +3.6795761469461986e-02 +-2.8076682880679589e+00 +1.7658998076408479e+00 +-3.1163728339678086e-02 +-4.3454975950961696e+00 +-1.4247852945382538e+00 +1.0683441030285992e-01 +-2.4251915230322347e+00 +1.3443815332610691e+00 +1.3499736517799768e-01 +-3.7475857364828173e+00 +-1.2090300352102725e+00 +2.3811573548090523e-01 +-2.2933804432798772e+00 +-7.9616019381184533e-01 +3.5806189036761121e-01 +-2.5491960359872659e+00 +-7.8925977604026787e-01 +3.6468354911018391e-01 +-2.5867922375214971e+00 +-1.9531047343820536e+00 +4.1361408659228344e-01 +-1.3658317676014016e+00 +-2.1229948172224661e-01 +5.8626922623068856e-01 +-3.7875010169999608e+00 +-2.0907168507779748e+00 +5.1223010354838283e-01 +-1.5172022467972104e+00 +-2.0907168507779748e+00 +5.1223010354838283e-01 +-1.5172022467972104e+00 +-1.4291601442029751e+00 +6.6767244078649979e-01 +-3.2336719298749874e+00 +-1.6334296940846944e+00 +6.1110404700367216e-01 +-2.4390650774070739e+00 +-8.3504976029108302e-01 +5.7448200490617451e-01 +-2.5146897140069959e+00 +-1.0684248923710709e+00 +5.6470922791845812e-01 +-2.3340135511132432e+00 +-1.0791905356312175e+00 +5.7163477647333971e-01 +-2.3843532627932671e+00 +-1.2141083574754692e+00 +6.0126625114186960e-01 +-2.5537045765479718e+00 +-2.1113750834449143e+00 +5.6343988360296826e-01 +-1.5843483276885766e+00 +-2.1113750834449143e+00 +5.6343988360296826e-01 +-1.5843483276885766e+00 +-1.5344019974588470e+00 +6.0345994570901040e-01 +-2.2961988358825818e+00 +-1.4701773601368231e+00 +6.1031939397637403e-01 +-2.3617845029832374e+00 +-1.4325579226980800e+00 +6.0819496801186623e-01 +-2.3511623833379325e+00 +-1.2101695688991350e+00 +6.1139025581343265e-01 +-2.3550302551325557e+00 +-2.1035794632466644e+00 +5.7640007457270337e-01 +-1.5414605606184109e+00 +-1.7514914570982332e+00 +6.7998106940227854e-01 +-2.4894682751790387e+00 +-2.5749649300438855e+00 +7.8628997879397355e-01 +-2.8233321969196354e+00 +-1.4517080588712057e+00 +6.4757133281128276e-01 +-2.3686413362270806e+00 +-1.4132806134586937e+00 +6.6644569846078261e-01 +-2.4386034007988449e+00 +-1.4670695288011761e+00 +6.5986141707684176e-01 +-2.2971877358275159e+00 +-1.3622391088062149e+00 +6.6757902122456370e-01 +-2.3345482437049543e+00 +-2.5252908263600893e+00 +8.1417581306725051e-01 +-2.7574458835842175e+00 +-2.1899913422914215e+00 +5.5714469719876036e-01 +-9.4974141139945745e-01 +-2.0549149235804789e+00 +8.0894419078331825e-01 +-2.5443107815917503e+00 +-2.1517775337093581e+00 +6.0884211027193313e-01 +-1.1094789552241826e+00 +-1.2071369178567586e+00 +7.4837796033941495e-01 +-2.3750034465319527e+00 +-2.2611984885571657e+00 +6.3008193834049031e-01 +-9.8961826873727021e-01 +-1.0202366701111314e+00 +4.5011587202698503e-02 +-2.6235569569726898e+00 +-9.7143263021749982e-01 +9.4676157311567671e-02 +-2.4379053880669646e+00 +-1.2523711564473674e+00 +1.4328174219529496e-01 +-2.3388623474868209e+00 +-8.1138046457945179e-01 +1.8026340039776606e-01 +-2.9909808045699036e+00 +-1.1714938142394913e+00 +2.3789080207152616e-01 +-2.2488490423047494e+00 +-8.7999260535334167e-01 +4.0675580637030806e-01 +-2.5032405153280064e+00 +-2.0316303839221139e+00 +3.7673544240283158e-01 +-1.2093508363776437e+00 +-2.0580714483443536e+00 +3.9890538824456240e-01 +-1.2649142272359359e+00 +-7.8151889994037504e-01 +4.3913446927351957e-01 +-2.5690970573886167e+00 +-7.4288093255929988e-01 +3.1809976216676544e-01 +-1.1641245803319000e+00 +-1.0844844101112439e+00 +4.5140576935579613e-01 +-2.4050814084927845e+00 +-1.1273259036576804e+00 +5.0881668751325215e-01 +-2.5835856305364477e+00 +-2.0982063507354205e+00 +5.1622304167868127e-01 +-1.5580988574136947e+00 +-2.0982063507354205e+00 +5.1622304167868127e-01 +-1.5580988574136947e+00 +-9.5804681351713272e-01 +5.8194538853562483e-01 +-2.4772364522790240e+00 +-1.3918649171483475e+00 +5.8655920768816761e-01 +-2.3535050673779172e+00 +-2.0241942774024397e+00 +6.7980537308804900e-01 +-2.4911034242330636e+00 +-2.0940117887585754e+00 +5.6178263638390580e-01 +-1.4984066245413499e+00 +-1.6839653382576312e+00 +6.8343300178738819e-01 +-2.5238202164487165e+00 +-2.5852844382221112e+00 +8.0136091286966216e-01 +-2.7933216730784509e+00 +-1.3023427170998938e+00 +6.8848437437502408e-01 +-2.5617127458917892e+00 +-1.1806503324537299e+00 +6.5103551140579652e-01 +-2.3269421559551953e+00 +-2.5155268231770047e+00 +7.9293445542215335e-01 +-2.6963226071359703e+00 +-2.1452960477256582e+00 +5.2361610435454409e-01 +-8.9950312857799419e-01 +-1.3983407078086652e+00 +6.5207866794982527e-01 +-2.2559284204209384e+00 +-1.2252242354091947e+00 +6.7663796328529691e-01 +-2.3518732683381538e+00 +-1.8961418510482908e+00 +7.4571304979104169e-01 +-2.5301884117549127e+00 +-9.9344235507344592e-01 +6.9086224829781684e-01 +-2.5626433884370328e+00 +-1.2053175088909465e+00 +6.8238743709780436e-01 +-2.3695703979371974e+00 +-2.1284200546061434e+00 +7.6961024992949234e-01 +-2.5211983525696748e+00 +-2.1284200546061434e+00 +7.6961024992949234e-01 +-2.5211983525696748e+00 +-1.2817177816280811e+00 +6.9043274727002335e-01 +-2.3792751304652850e+00 +-1.1983169276970493e+00 +7.3480713615351978e-01 +-2.6289528705059775e+00 +-1.4575573391512355e+00 +7.2756826133214769e-01 +-2.4943807641514106e+00 +-1.3276092927379650e+00 +7.2519407646013889e-01 +-2.4283140298912782e+00 +-2.2204549744843214e+00 +5.8345989129176756e-01 +-9.2800926869816902e-01 +-2.2387318467673833e+00 +6.0969444281858742e-01 +-9.5492501446181788e-01 +-2.2318686045215550e+00 +6.1752637793348275e-01 +-9.8431982341316027e-01 +1.4142305251565921e+00 +-4.3306100002729407e-02 +-2.5852821430316628e+00 +-1.4581041265034997e+00 +7.6823428747023095e-02 +-2.4258747217367573e+00 +-1.0616379540832681e+00 +7.2730287545389516e-02 +-2.3715842068997919e+00 +-1.3064336030451569e+00 +1.7776947154089759e-01 +-2.3448269784718612e+00 +-8.3290002798985585e-01 +1.8050713679900435e-01 +-2.5020908716771952e+00 +-1.3462946162627021e+00 +1.9697566203873781e-01 +-2.4164864090060498e+00 +-1.2416794176957719e+00 +1.9124337544500403e-01 +-2.3289023583883450e+00 +-1.3009740777362342e+00 +2.0380748697771151e-01 +-2.3269682025806655e+00 +-1.2515523504347397e+00 +2.3326371305542523e-01 +-2.3787583802750851e+00 +-1.1768679519697443e+00 +2.3049384868389536e-01 +-2.3151486494125595e+00 +3.7284127284647045e-01 +2.4343850768820213e-01 +-2.6947174074056730e+00 +-1.1869106192976522e+00 +3.0754242392002790e-01 +-2.2360143797940202e+00 +-6.4343164303712663e-01 +5.1528550636234582e-01 +-4.7703649517422146e+00 +-4.9994200454533877e-01 +4.3439184010769188e-01 +-3.5176837128585281e+00 +-2.2420092417908385e-01 +4.5158048836623804e-01 +-3.6359502237692269e+00 +-7.5483857484181571e-01 +4.6193714655066653e-01 +-2.6260952371875801e+00 +-8.8661225191517534e-01 +5.5550276551530808e-01 +-3.5287056645835007e+00 +-1.4742557234234066e+00 +4.8576278747399765e-01 +-2.2224369394091092e+00 +-2.0754240434611995e+00 +4.7345996505405430e-01 +-1.2875293561491683e+00 +-2.0824101949641918e+00 +5.1730579057117143e-01 +-1.4797543212554807e+00 +-8.9949332450687514e-01 +5.8333019748311477e-01 +-2.4463206432954565e+00 +-2.0348519073649265e+00 +6.6449225830670711e-01 +-2.4795578693844385e+00 +-2.0348519073649265e+00 +6.6449225830670711e-01 +-2.4795578693844385e+00 +-2.0929460954955119e+00 +5.6148967224940161e-01 +-1.4967502735156641e+00 +-1.6832674388226447e+00 +6.6981199586054863e-01 +-2.4718446791331368e+00 +-2.0918797936499907e+00 +7.0292436194413865e-01 +-2.5201989885009803e+00 +-1.6393239443324523e+00 +6.7052360307937320e-01 +-2.4677749515413465e+00 +-1.4718483388762087e+00 +6.3670277409116538e-01 +-2.3697296202420568e+00 +-2.0696542383045826e+00 +5.8347759505395680e-01 +-1.4469781539357980e+00 +-2.6317258776645627e+00 +8.3434961005698272e-01 +-2.8255370371024906e+00 +-2.0557266837722481e+00 +6.0454098821368885e-01 +-1.3236809519174619e+00 +-2.0597644521578542e+00 +6.0295636458164703e-01 +-1.3072787171220634e+00 +-2.0798715816336206e+00 +6.0195737069780808e-01 +-1.2777426753377956e+00 +-2.0921718183329543e+00 +6.0262668715089718e-01 +-1.2659637506799406e+00 +-1.2611423078350217e+00 +7.0461424240727355e-01 +-2.3712701020726938e+00 +-2.1141994404191760e+00 +6.0559380277878028e-01 +-1.2658691611701263e+00 +-1.2528133433384490e+00 +7.1680643812448974e-01 +-2.4206811112106168e+00 +-2.2062106246703705e+00 +5.8852350113787044e-01 +-9.8738005879429602e-01 +-2.2319274334990391e+00 +5.9732706072021702e-01 +-9.4986482877301848e-01 +-2.2319274334990391e+00 +5.9732706072021702e-01 +-9.4986482877301848e-01 +-1.0338187185641248e+00 +8.1493679995639157e-01 +-2.5982536335967614e+00 +-2.2220207540439207e+00 +6.2397644150099896e-01 +-9.8707331096278683e-01 +-1.1844432779626741e+00 +1.1167682045120779e-01 +-2.3519226394030581e+00 +-1.3981747079421989e+00 +1.3641888874824537e-01 +-2.4255220765518111e+00 +-1.1609130426413368e+00 +2.0393319498434012e-01 +-2.2792545030205194e+00 +-1.0377836209144209e+00 +2.2464446914599870e-01 +-2.4316821227952987e+00 +-1.2610632464873610e+00 +2.7789262304679507e-01 +-2.2489271955011887e+00 +-9.0750460320989546e-01 +2.9603927405915520e-01 +-2.5252611665100182e+00 +-1.2929386029125514e+00 +3.1462500135725879e-01 +-2.3461168089089877e+00 +-7.2590157603670313e-01 +4.0111400026016353e-01 +-2.8414876580470350e+00 +-8.9504972324312515e-01 +4.1522839428933456e-01 +-2.4425829658356522e+00 +-1.9772799315993315e+00 +3.9364931905391787e-01 +-1.3462838558893604e+00 +-1.4127302905335668e+00 +4.4838520397219372e-01 +-2.3177117601986552e+00 +-1.4921466655222728e+00 +4.6158552446967061e-01 +-2.2042469675777299e+00 +-5.4399999349297401e-01 +6.2012633691709051e-01 +-4.4362987497204127e+00 +-2.0850303157199064e+00 +4.2732993655944373e-01 +-9.8674752603797478e-01 +-2.0780871157889758e+00 +4.2082564207078993e-01 +-8.9397723512248106e-01 +-2.5755920520640512e+00 +6.8816699354609812e-01 +-2.8382898143104511e+00 +-7.1621859998573878e-01 +5.7404191451818709e-01 +-2.7656941784980211e+00 +-9.9178444931881904e-01 +5.4903920333120548e-01 +-2.3956231905010523e+00 +-8.5492795143998002e-01 +5.6166061829313396e-01 +-2.5596550628368773e+00 +-2.5816191841491376e+00 +7.3216642527418141e-01 +-2.8513817562202828e+00 +-2.0004247986930026e+00 +6.7320260740080295e-01 +-2.4780722037793974e+00 +-1.9572701432182116e+00 +6.9228466333844829e-01 +-2.4707294105951054e+00 +-1.5164789622139709e+00 +6.3820968516021603e-01 +-2.3770924957778750e+00 +-1.5956022086831823e+00 +6.7792053293054000e-01 +-2.4429089886687647e+00 +-1.5430654504630701e+00 +6.4890223084748788e-01 +-2.3653731765199737e+00 +-2.0998147485243277e+00 +6.0276990672889341e-01 +-1.5799928296108467e+00 +-1.4467057566684804e+00 +6.8791159186834161e-01 +-2.5332816325929475e+00 +-1.0883127796086789e+00 +6.5708457883011140e-01 +-2.4397394306737215e+00 +-1.5523928575371395e+00 +6.7371529713318257e-01 +-2.4485113492691442e+00 +-2.1105533587488483e+00 +6.0663569292902431e-01 +-1.5672973871456251e+00 +-1.4851427511902282e+00 +7.0641077026999888e-01 +-2.5600043607774068e+00 +-2.0282651445973268e+00 +7.3247856171062553e-01 +-2.5160297781775123e+00 +-2.0370462798591711e+00 +7.3131237965350726e-01 +-2.4884616494852545e+00 +-2.0762291455350668e+00 +6.0398131287324097e-01 +-1.4576237681775099e+00 +-1.7493034364063802e+00 +7.3173130787348795e-01 +-2.5069943341055869e+00 +-9.8654864992191438e-01 +6.6777972978863409e-01 +-2.3857635339214900e+00 +-2.0796680630600552e+00 +7.6906783595671013e-01 +-2.4933819332548719e+00 +-2.0730300062295091e+00 +6.0188624907632593e-01 +-1.2897873603706864e+00 +-1.3157764345775993e+00 +7.2564748797969980e-01 +-2.4284982519093083e+00 +-2.0024948500301591e+00 +8.0172358040903036e-01 +-2.5428223262798029e+00 +-2.0761312470615878e+00 +6.2462261160220722e-01 +-1.3016411785093847e+00 +-2.1136470019232436e+00 +6.2004716764453416e-01 +-1.2211604514828898e+00 +-1.2278747345530319e+00 +7.4408166661561748e-01 +-2.3762043727558955e+00 +-2.7004556344479198e+00 +9.6738401767557036e-01 +-2.9682137103812094e+00 +-2.3721407560810546e+00 +9.4191017722150916e-01 +-2.9467067596153074e+00 +-1.3959406798486644e+00 +9.8422535607622430e-02 +-2.4244962107751973e+00 +1.4481809851596508e+00 +4.1735830324755488e-02 +-3.8930288916620439e+00 +-1.3734103369766857e+00 +1.8562115559240316e-01 +-2.4126561463091991e+00 +-9.6146596338981172e-01 +2.1145382863130141e-01 +-2.4885038468944627e+00 +-1.3442047145760969e+00 +3.0864747980808993e-01 +-2.4102261179386208e+00 +-1.2889101457096173e+00 +3.1925766750061352e-01 +-2.4578860150797448e+00 +-1.1552602350173582e+00 +3.2808846602149150e-01 +-2.3879925148277890e+00 +-4.6443306220240915e-01 +4.8297861114699814e-01 +-4.1753076690094204e+00 +-7.1565224748520884e-01 +4.2217139105233958e-01 +-2.7139641181698178e+00 +-1.9549566193466392e+00 +3.9361562818334533e-01 +-1.3910902110699668e+00 +-7.3063542606038090e-01 +4.4951770337193864e-01 +-2.8547004289867282e+00 +-1.9935174666059052e+00 +4.2401588356512360e-01 +-1.3198015671092802e+00 +-1.9535115594010508e+00 +4.3166827798186874e-01 +-1.4076207389921531e+00 +-1.9317499156430449e+00 +4.4829549646511963e-01 +-1.4189863006797014e+00 +-2.0192321059943339e+00 +4.3905970711985720e-01 +-1.2593264249825471e+00 +-2.0195157218369779e+00 +4.3841430289895883e-01 +-1.2427356868524175e+00 +-2.0300127577306246e+00 +4.3876296075483989e-01 +-1.2403884268344412e+00 +-2.0340511088071951e+00 +4.3756922037128509e-01 +-1.2107412847080636e+00 +-2.0079228295005169e+00 +4.4771162699407352e-01 +-1.3089015727759934e+00 +-2.0651894069419687e+00 +4.3783496135958061e-01 +-1.1715546005412383e+00 +-2.0776855009676889e+00 +4.2214138278864199e-01 +-9.9182042292874473e-01 +-1.9973859372650045e+00 +4.4388468896490313e-01 +-1.2624112514732329e+00 +-2.0726938061625879e+00 +4.1982001346080705e-01 +-9.6244290668592214e-01 +-2.0631294369218396e+00 +4.3097103474985549e-01 +-1.0726209507837374e+00 +-2.0909391079456099e+00 +4.3380663718885637e-01 +-1.0692192375479526e+00 +-2.0743797336039553e+00 +4.1437165812736448e-01 +-8.7725683973791424e-01 +-2.0155209602909423e+00 +4.5415750829342477e-01 +-1.2925962996745977e+00 +-2.0153781364773438e+00 +4.5271197086142517e-01 +-1.2786453931917172e+00 +-2.0153781364773438e+00 +4.5271197086142517e-01 +-1.2786453931917172e+00 +-2.0895407606779814e+00 +4.2667062912061327e-01 +-9.6298552664938275e-01 +-1.8980837175635243e-01 +6.3438902412869613e-01 +-3.7734186717951150e+00 +-1.4885648232238653e+00 +5.6312919583977517e-01 +-2.4128645460328584e+00 +-1.5672938365642113e+00 +5.8878641802715248e-01 +-2.4821137170789198e+00 +-7.1898119882675049e-01 +5.8111078519361004e-01 +-2.6621679270946088e+00 +-2.0789141148431534e+00 +6.3555435946634931e-01 +-2.4625398855665499e+00 +-2.1210011481200589e-01 +6.9285725023536282e-01 +-3.7243430468494441e+00 +-2.0853179848949970e+00 +6.5418401698886752e-01 +-2.4585071631355748e+00 +-2.0106842814661157e+00 +6.5649166306978812e-01 +-2.4740912731642037e+00 +-2.1066883118958186e+00 +6.7266577580079689e-01 +-2.4759308018051014e+00 +-2.1066883118958186e+00 +6.7266577580079689e-01 +-2.4759308018051014e+00 +-7.8608262283484553e-01 +6.1029370471109956e-01 +-2.5327587715087243e+00 +-2.0751314159398895e+00 +6.7452140684668882e-01 +-2.4805313627381120e+00 +-2.0751314159398895e+00 +6.7452140684668882e-01 +-2.4805313627381120e+00 +-7.8329195636841897e-01 +6.3105258176135148e-01 +-2.6540731637164359e+00 +-1.2725223281920603e+00 +6.4411741616350204e-01 +-2.5359169448536711e+00 +-1.9957766838336291e+00 +6.8459804604920682e-01 +-2.4886890731771381e+00 +-1.9957766838336291e+00 +6.8459804604920682e-01 +-2.4886890731771381e+00 +-1.0303718170113687e+00 +6.5433272854882973e-01 +-2.6901603411956656e+00 +-2.5559062217814965e+00 +7.7939111899583435e-01 +-2.8536486732912887e+00 +-8.1811057359267658e-01 +6.3398148076524274e-01 +-2.5978428382203522e+00 +-1.2702076345359163e+00 +6.3969432159313122e-01 +-2.4054206607950888e+00 +-1.4095489757381530e+00 +6.2146459960534139e-01 +-2.2739590768638367e+00 +-7.4095032029787256e-01 +6.4353563841530714e-01 +-2.6804092954458545e+00 +-1.8279509405106655e+00 +6.9022405004077825e-01 +-2.4891901930972162e+00 +-1.7190333329393070e+00 +6.8271215756780090e-01 +-2.4709966769577703e+00 +-2.0731728853221498e+00 +5.5372535816044965e-01 +-1.2780311358666248e+00 +-2.0731728853221498e+00 +5.5372535816044965e-01 +-1.2780311358666248e+00 +-8.0720376006068861e-01 +6.5519566066170409e-01 +-2.5911154581153499e+00 +-1.4089661764733061e+00 +6.5387529481882267e-01 +-2.4122400302518607e+00 +-1.5498274888468595e+00 +6.7857760209948093e-01 +-2.4321734543291287e+00 +-1.4893416064438305e+00 +6.3447407250560450e-01 +-2.2297587609221323e+00 +-1.5458291317328898e+00 +6.8663415302539144e-01 +-2.5172421220129237e+00 +-8.0210223146714810e-01 +6.4691124505691566e-01 +-2.5518536564095116e+00 +-8.4623795150042791e-01 +6.6341639751942338e-01 +-2.5437509967100520e+00 +-7.9573151410220488e-01 +6.5506318660852803e-01 +-2.5570749013604130e+00 +-1.0359853214156336e+00 +6.5181415821351141e-01 +-2.4290839008799172e+00 +-1.1921871876504626e+00 +6.4853313380470567e-01 +-2.3542912728120688e+00 +-9.3932375190256168e-01 +6.6750698931409136e-01 +-2.4993935094313859e+00 +-2.0908613762717887e+00 +6.0458114235830762e-01 +-1.5093105256430821e+00 +-2.5535364371567115e+00 +8.2457390552333432e-01 +-2.8495315618183166e+00 +-2.5535364371567115e+00 +8.2457390552333432e-01 +-2.8495315618183166e+00 +-1.8842006488855221e+00 +7.3622042684024935e-01 +-2.5333613294654325e+00 +-8.9543553374912432e-01 +6.7340010319377108e-01 +-2.5177007261475755e+00 +-1.0977894160833288e+00 +7.0608768100031549e-01 +-2.6854035328348904e+00 +-1.4770367561238018e+00 +7.1448106881501028e-01 +-2.5350727757665963e+00 +-2.1036616362329621e+00 +6.4816620163679306e-01 +-1.5311390098975237e+00 +-2.2351782645982352e+00 +5.7413747380481683e-01 +-9.2301816716698759e-01 +-2.2398390063717217e+00 +5.7291608679146511e-01 +-9.0281895291588432e-01 +-1.1175868569953928e+00 +7.3465106259600343e-01 +-2.4105914204648240e+00 +-2.1293672373796850e+00 +6.0154745042132451e-01 +-1.1326055913021758e+00 +-2.0596573957585127e+00 +8.2569984566943722e-01 +-2.5096976825126300e+00 +-2.0555035519087075e+00 +6.4669601726249193e-01 +-1.3694035314105328e+00 +-2.0660212051116198e+00 +6.4368744297669356e-01 +-1.3310887835563383e+00 +-2.2065064231793396e+00 +6.0386932142001082e-01 +-9.9552278282057982e-01 +-2.3864049948755364e+00 +9.5622067664613120e-01 +-3.0032652316422337e+00 +-2.2182258154261878e+00 +6.1976222658619495e-01 +-1.0297703860424003e+00 +-1.2172989386843975e+00 +8.1104144969068492e-01 +-2.4422041139930406e+00 +-1.2054200433724469e+00 +7.9700119961442395e-01 +-2.3812425283632144e+00 +1.4224075955396311e+00 +-3.2082776210769638e-02 +-2.6206478481166204e+00 +-1.0894789314200857e+00 +1.1261855060861302e-02 +-2.5440244396377918e+00 +-1.2762061527078092e+00 +5.9564011848044399e-02 +-2.2127594646266004e+00 +-1.2780859016632229e+00 +6.2974927596066141e-02 +-2.2128894220670543e+00 +-1.2496177137657942e+00 +7.2117559035128051e-02 +-2.3355288286446072e+00 +-1.4894440691251616e+00 +9.0139848542805018e-02 +-2.4524873282013342e+00 +1.6341677310977443e+00 +3.3509844699230384e-03 +-4.1720343172000520e+00 +-1.2089241301343823e+00 +9.2903067840817255e-02 +-2.3247132145717928e+00 +1.4621134515157173e+00 +3.5217052336866762e-02 +-3.9064753828666703e+00 +-1.0352260849067640e+00 +1.6402787087237827e-01 +-2.5895505396811105e+00 +-1.3770700765310713e+00 +2.2080595155309127e-01 +-2.4112847272886033e+00 +-8.7014854162067956e-01 +2.0956304875151793e-01 +-2.5259576431136588e+00 +-9.4577654802109468e-01 +2.1083011607664173e-01 +-2.5084033791222544e+00 +-1.0333532260937071e+00 +2.2227823098773611e-01 +-2.3444489050906370e+00 +-1.3037173297756162e+00 +2.5068303297345818e-01 +-2.3600886743417182e+00 +-1.2998764552553081e+00 +2.4958331903886954e-01 +-2.3563965722902638e+00 +-1.3706078604167256e+00 +3.2775489663946444e-01 +-2.4012585491458682e+00 +-1.3476282230162997e+00 +3.3937982900392893e-01 +-2.4695401487717601e+00 +-1.2984418946600864e+00 +3.3694826430429675e-01 +-2.3142829923127284e+00 +-5.4812637343396031e-01 +4.7470629374971851e-01 +-4.2993600055888921e+00 +-6.6474056300005413e-01 +5.2189062484982873e-01 +-4.8158138689383607e+00 +-1.5595718349167755e+00 +4.1950989540751793e-01 +-2.4349893859621066e+00 +-1.2524592475337502e+00 +3.3005445123528193e-01 +-1.3726429419217554e+00 +-1.0392884015945694e+00 +4.0595168918773111e-01 +-2.3578837872165015e+00 +-1.1291664371674988e+00 +4.0803334865704666e-01 +-2.3386514805675720e+00 +-3.4999793408017676e-01 +5.0046848513842246e-01 +-3.9340929173996542e+00 +-1.0976351618554263e+00 +4.4990987079415456e-01 +-2.5703156409034817e+00 +-1.9999069441124253e+00 +4.0223785953596286e-01 +-1.3435874872096523e+00 +-7.0290540199345886e-01 +4.5452284748911531e-01 +-2.7466515017636555e+00 +-7.2824739371514069e-01 +4.5885925594267485e-01 +-2.7408894353792999e+00 +-1.9530078766370154e+00 +4.1151162373539352e-01 +-1.3864898079905503e+00 +-1.9530078766370154e+00 +4.1151162373539352e-01 +-1.3864898079905503e+00 +-1.5004448607808394e+00 +4.4451312044334157e-01 +-2.2019012705943113e+00 +-1.9679316988304743e+00 +4.1135147938797484e-01 +-1.3643127346198058e+00 +-9.3831899691401044e-01 +4.5552336219276368e-01 +-2.4020427535762319e+00 +-1.3490482327974107e+00 +4.9310692602375306e-01 +-2.3910478110520175e+00 +-2.0561861345238004e+00 +4.1923406148470832e-01 +-1.1421590972086759e+00 +-1.9254058423876452e+00 +4.4111764685574761e-01 +-1.4121739564872231e+00 +-1.9254058423876452e+00 +4.4111764685574761e-01 +-1.4121739564872231e+00 +-1.9391268358681522e+00 +4.4183659835699207e-01 +-1.4022529034811304e+00 +-1.9519691634261271e+00 +4.4875600299725610e-01 +-1.4174079579930552e+00 +-2.0067440720423049e+00 +4.4217638455042485e-01 +-1.3016893546294925e+00 +-2.0676146804254900e+00 +4.2563978796948049e-01 +-1.0715694254012968e+00 +-2.0779251453722551e+00 +4.3135692700747630e-01 +-1.0417483636647185e+00 +-2.0828670013147943e+00 +4.2771950266714448e-01 +-9.6936715230972614e-01 +-2.0796851019266440e+00 +4.3600796346603315e-01 +-1.0351276071937243e+00 +-2.0825785433214072e+00 +4.2168931123278430e-01 +-8.8606160997475580e-01 +-2.0584132574874809e+00 +4.5804311777343309e-01 +-1.1941828201808251e+00 +-2.1408481533213721e+00 +5.9255002002221080e-01 +-2.4856309246730928e+00 +-1.5307452102167327e+00 +5.6139663094373882e-01 +-2.4789231351686802e+00 +-1.4037293195452134e+00 +5.3211439797463900e-01 +-2.2619710193406970e+00 +-1.0427630333111071e+00 +5.5873515057297651e-01 +-2.3750632117729129e+00 +-1.1190911737684388e+00 +6.0722895613974781e-01 +-2.6242027663932150e+00 +-2.4859486689852646e+00 +7.0924962245487910e-01 +-2.6818752014507545e+00 +-1.6962932130562682e+00 +6.3643895244985427e-01 +-2.4722419073317567e+00 +-8.4858765876389874e-01 +6.1024309806375032e-01 +-2.5319313188499737e+00 +-9.4209128223870864e-01 +6.1405383682554060e-01 +-2.4312948810463455e+00 +-1.0322307936299040e+00 +6.2041115627087040e-01 +-2.4266555832851258e+00 +-1.0360901072581676e+00 +6.2166718702869117e-01 +-2.4176233224638031e+00 +-2.5625206394403413e+00 +7.7462076179946926e-01 +-2.8336028287123414e+00 +-2.5625206394403413e+00 +7.7462076179946926e-01 +-2.8336028287123414e+00 +-7.5136965901831254e-01 +6.3322612692047398e-01 +-2.6786737763925652e+00 +-1.9749647538750419e+00 +6.9206290479548427e-01 +-2.4685175500529568e+00 +-1.3441246956531312e+00 +6.1047725045103685e-01 +-2.2096221433500842e+00 +-1.1687307599119043e+00 +6.3612238819841471e-01 +-2.4002406465489399e+00 +-1.3357495963176329e+00 +6.5113803912803303e-01 +-2.4254144319805504e+00 +-1.6811675019172259e+00 +6.8205361685041366e-01 +-2.4660605056121181e+00 +-1.5050392729020836e+00 +6.6767770377807323e-01 +-2.4896581042359451e+00 +-9.7561717448216223e-01 +6.4038034479336159e-01 +-2.4503732877261206e+00 +-1.4929958532166139e+00 +6.6382718252281403e-01 +-2.4485040486974787e+00 +-1.3715603724556007e+00 +6.6240807531573964e-01 +-2.4078777910781719e+00 +-2.1673132508152331e+00 +5.2171947112164851e-01 +-9.1771171236976956e-01 +-2.5888129884288853e+00 +8.2006002310283199e-01 +-2.8403080897210344e+00 +-2.6042880547946430e+00 +8.2359180581073776e-01 +-2.8312015642988833e+00 +-2.5890250389512723e+00 +8.2801235520510397e-01 +-2.8520701414352772e+00 +-1.9487783635273723e+00 +7.2977492735863514e-01 +-2.4866047051267475e+00 +-1.1630132898114176e+00 +6.7125045624325963e-01 +-2.4317858822562091e+00 +-1.1261406051240661e+00 +6.6791872940606378e-01 +-2.4291448880688229e+00 +-1.1870414421981363e+00 +7.0849957976354516e-01 +-2.6086251798378393e+00 +-2.0296340627273532e+00 +7.5438208294245990e-01 +-2.4980830747394411e+00 +-2.1305475745235580e+00 +5.8925603853213493e-01 +-1.1643667951290153e+00 +-2.1305475745235580e+00 +5.8925603853213493e-01 +-1.1643667951290153e+00 +-2.2174072076265676e+00 +5.6062124585149031e-01 +-8.9763576731231853e-01 +-2.0770825651839004e+00 +6.1771146548148481e-01 +-1.3021995570695912e+00 +-2.1967448188785750e+00 +5.7209632992450876e-01 +-9.5240382501665299e-01 +-2.0818502349776047e+00 +6.1740020605602841e-01 +-1.2961036760866276e+00 +-2.2003287763021464e+00 +5.7981723199638513e-01 +-9.8953151778651560e-01 +-2.1184066929360594e+00 +6.0377944074772216e-01 +-1.1655306909714396e+00 +-2.1532771668845503e+00 +5.9964566866920210e-01 +-1.0854278172377441e+00 +-1.1803438095415855e+00 +7.3945600550018420e-01 +-2.4194199463889068e+00 +-2.1679536046780279e+00 +6.0095124676123801e-01 +-1.0814118031232514e+00 +-1.1605750578294165e+00 +7.3111936975213543e-01 +-2.3578427084718272e+00 +-2.1925624233830185e+00 +6.0243149144769637e-01 +-1.0235074817684116e+00 +-2.0764711304754044e+00 +6.4879504533064758e-01 +-1.3217139859177076e+00 +-1.0043322232839329e+00 +7.7529466264648594e-01 +-2.5428708445527102e+00 +-2.2340008843042103e+00 +6.2200618785711848e-01 +-9.8675119377944664e-01 +-1.1254538425746381e+00 +8.6322634526813147e-01 +-2.8802437101280862e+00 +-8.2341546615048922e-01 +8.5168029244050303e-01 +-2.8748510126723561e+00 +-1.9934808155752799e+00 +9.3055881103078897e-01 +-2.7829424552004571e+00 +-9.1136851678365927e-01 +1.0323468824287061e-02 +-2.7588245852265456e+00 +-9.4081782434842676e-01 +1.2124213943637746e-02 +-2.7176977987219253e+00 +-8.6394549553365185e-01 +6.7915495087406533e-02 +-1.5399630336973087e+00 +-1.2804472530117768e+00 +5.7734054378006210e-02 +-2.3256860157735950e+00 +-1.1970588828631332e+00 +6.1933937082284354e-02 +-2.3182144624721293e+00 +-1.1970588828631332e+00 +6.1933937082284354e-02 +-2.3182144624721293e+00 +-1.0182083781661084e+00 +5.4412103383434704e-02 +-2.5786499355498047e+00 +-1.0288744969142560e+00 +5.4364376154616915e-02 +-2.5908094298672260e+00 +-1.1872616939423783e+00 +7.0089663103839739e-02 +-2.4734278437857955e+00 +-1.1828607055719125e+00 +8.2129582707327259e-02 +-2.3994588395953254e+00 +-1.3935857754033854e+00 +8.8718732509895662e-02 +-2.4509713316715191e+00 +-1.4127960131601873e+00 +8.9314035723200499e-02 +-2.4368256353039612e+00 +-1.4577063609216365e+00 +9.0671272467787764e-02 +-2.4324211128128299e+00 +-1.3445929485068182e+00 +8.8722245674738145e-02 +-2.4216300950361083e+00 +-1.1645053569550825e+00 +8.5961608140734377e-02 +-2.3545351427543868e+00 +-1.1818162597372832e+00 +1.0028374167768918e-01 +-2.3712465586537377e+00 +-8.3559520172554269e-01 +1.5333313724448142e-01 +-2.9512641491546714e+00 +-1.3153094636308764e+00 +1.7321155297060065e-01 +-2.3576788010210485e+00 +-1.2744225162372902e+00 +2.0869042375661367e-01 +-2.4211872622196600e+00 +-8.3661229475825194e-01 +1.9769994152748879e-01 +-2.5370049877017697e+00 +-1.2315795885514729e+00 +2.0738836544883879e-01 +-2.4382458325570822e+00 +-1.4414885130872175e+00 +2.2279005948735819e-01 +-2.4196669815291281e+00 +-1.3469885035605715e+00 +2.2179329982236451e-01 +-2.4320663805707849e+00 +-8.7751158834816145e-01 +2.1099258136807403e-01 +-2.5124986443366728e+00 +-9.1170409044186407e-01 +2.0860690057782660e-01 +-2.4195143494617777e+00 +1.2179843669634620e+00 +1.7896246705259874e-01 +-3.5776395074929606e+00 +-1.4373590189178551e+00 +2.2780853222934999e-01 +-2.4213669722776174e+00 +-9.8436092650472984e-01 +2.1149487414286491e-01 +-2.4493076421983004e+00 +-1.2316158482758119e+00 +2.2121879098357500e-01 +-2.4642114856730242e+00 +-8.2207117565507326e-01 +2.1713706946312408e-01 +-3.0027624575512704e+00 +-8.7709881270683998e-01 +2.1724870004623414e-01 +-2.5256302157508688e+00 +-1.0303803091025658e+00 +2.2349852235217280e-01 +-2.6397611711289497e+00 +-1.2450995508158014e+00 +2.2652771532268035e-01 +-2.3151642835157689e+00 +1.2330536971291024e+00 +1.9199313906808863e-01 +-3.5882062442141369e+00 +-1.1226263540060371e+00 +2.2881208815312956e-01 +-2.3810240696431788e+00 +-1.1215064550734997e+00 +2.2944459108116869e-01 +-2.3390923097331142e+00 +-9.8261548609484384e-01 +2.2874938959487809e-01 +-2.4696297724300886e+00 +-7.4054516945207305e-01 +2.4394857796734268e-01 +-2.6115112554595794e+00 +-7.9625095078350039e-01 +2.4975546667282472e-01 +-2.5553647897632912e+00 +-8.0327200212762473e-01 +2.7707208501443287e-01 +-2.5602172656395892e+00 +-7.7494738781572503e-01 +2.7657494206960992e-01 +-2.6047375256303549e+00 +-8.9768586258711214e-01 +2.9102338650501047e-01 +-2.8274267596094602e+00 +-1.0715487729587447e+00 +2.8113812260193854e-01 +-2.3826774807027920e+00 +-7.7990995090148585e-01 +2.8369148410054085e-01 +-2.6187063588753121e+00 +-1.2213545514852790e+00 +3.1901373900637459e-01 +-2.4773649241853839e+00 +-1.5028626356777370e+00 +3.3064006171600513e-01 +-2.4245270385507145e+00 +-1.2453861997865945e+00 +3.1694404711209118e-01 +-2.3515460373426960e+00 +-1.1032908830490511e+00 +3.2882873950731739e-01 +-2.5592390249553003e+00 +-5.6748649610705149e-01 +4.7199126972846733e-01 +-4.3087099692124156e+00 +-5.6748649610705149e-01 +4.7199126972846733e-01 +-4.3087099692124156e+00 +-2.5346831722748991e-01 +4.3830869230503711e-01 +-3.5956253958682276e+00 +-4.1909293548666215e-01 +4.7451592307162144e-01 +-4.0685128902266872e+00 +-5.0106758915215055e-01 +4.9348082265742094e-01 +-4.2023601752419610e+00 +-1.4435216281611714e+00 +4.1862528906347907e-01 +-2.4238273306348943e+00 +-1.5252387420957694e+00 +4.2491836517051579e-01 +-2.4545342040283682e+00 +-7.9191742586267466e-01 +4.4391139943882146e-01 +-2.8966387288265611e+00 +-1.1903190831164396e+00 +3.3474955880459728e-01 +-1.3970239406026843e+00 +-8.1264821483347871e-01 +4.3783491024164628e-01 +-2.7873237246847444e+00 +-2.6051459961252982e-01 +4.6384582658763485e-01 +-3.5964005034212909e+00 +-3.6254090176163661e-01 +4.9231039657148068e-01 +-3.8808742887315439e+00 +-3.6965146071180538e-01 +5.0413836144891078e-01 +-3.9727753987893357e+00 +-8.7548528808555603e-01 +4.1305414590186673e-01 +-2.4883695183727013e+00 +-1.1445132595596770e+00 +4.2862761652750397e-01 +-2.4120322829657521e+00 +-2.0714648439703862e+00 +3.8555352395845144e-01 +-1.1329361247019496e+00 +-7.8956504907412761e-01 +4.9727722380233225e-01 +-2.9911944257614644e+00 +-2.0806354605990665e+00 +3.7856064429396324e-01 +-9.8976282300980245e-01 +-2.0376774862896823e+00 +3.9678313184111152e-01 +-1.2300039101900022e+00 +-1.9710311625568586e+00 +4.0786212845662162e-01 +-1.3599538687539532e+00 +-7.7879928498236251e-01 +4.5159810786382915e-01 +-2.5673956328821381e+00 +-2.5875587717458792e+00 +5.8025197480680513e-01 +-2.8742645904905806e+00 +-2.5875587717458792e+00 +5.8025197480680513e-01 +-2.8742645904905806e+00 +-1.3320779944086361e+00 +4.7551856517585361e-01 +-2.4815224055066145e+00 +-1.1336411662117258e+00 +4.5843398304819299e-01 +-2.3912222239491201e+00 +-1.6395757946153458e-01 +5.4091990228078557e-01 +-3.6184324430808075e+00 +-1.4190182580244781e+00 +4.6758767474882834e-01 +-2.2283134616997056e+00 +-1.9611328939244626e+00 +4.3160053106569468e-01 +-1.3796512139892743e+00 +-1.9811770189945490e+00 +4.3154394410186531e-01 +-1.3515335096530994e+00 +-1.4064917320513022e+00 +4.9937274151910688e-01 +-2.4891774545366729e+00 +-1.9853347687185487e+00 +4.4263186076715794e-01 +-1.3360370473103924e+00 +-1.1007867244584046e+00 +5.1539643196181451e-01 +-2.6419903585634219e+00 +-1.1040942633423279e+00 +5.1185676943809422e-01 +-2.6001511962577255e+00 +-2.0690628758995433e+00 +4.1247043381343240e-01 +-9.1965553468084704e-01 +-2.0568365037662524e+00 +4.3857865001965551e-01 +-1.1730744378375229e+00 +-2.0793533874310719e+00 +4.1767954351613362e-01 +-9.3593343208045698e-01 +-2.0220313772958702e+00 +4.6000015258357213e-01 +-1.2870960077680724e+00 +-2.0106358600625467e+00 +4.6222519399914280e-01 +-1.3104547431462745e+00 +-2.0154477821837808e+00 +4.6156249795106774e-01 +-1.2908407948414997e+00 +-1.8934407585892812e-01 +6.1336621853131190e-01 +-3.7019199909682872e+00 +-2.0415718910354648e+00 +4.5996130265045698e-01 +-1.2464192757156420e+00 +-5.5980350938949464e-01 +7.3301025164129485e-01 +-4.6286147021378978e+00 +-1.5298015451299640e+00 +5.7064341079479108e-01 +-2.4820971472368680e+00 +-1.3535688855470727e+00 +5.3712578974433867e-01 +-2.3053013136000877e+00 +-1.3401030410002346e+00 +5.5759294844646534e-01 +-2.4387637884221984e+00 +-7.0586782071109511e-01 +5.7379069394663340e-01 +-2.8016435069205143e+00 +-1.4105942784315648e+00 +5.7385929734451246e-01 +-2.5027918158160598e+00 +-1.2873999097691724e+00 +5.3223642652779346e-01 +-2.2369452867146604e+00 +-1.4509440852800244e+00 +5.6263343470829918e-01 +-2.3993034526474211e+00 +-9.8558180092504866e-01 +5.5126307826265186e-01 +-2.3855746393104931e+00 +-2.0753845353519891e+00 +5.2227545009791387e-01 +-1.4760672658748986e+00 +-7.0631621519880228e-01 +5.9890719568530193e-01 +-2.7689190134528969e+00 +-7.4125004448600884e-01 +5.8208526248227199e-01 +-2.6781439421109150e+00 +-1.6893199017990985e+00 +6.2923328851877514e-01 +-2.4680385569196903e+00 +-1.5235223825170470e+00 +5.9515794432565139e-01 +-2.3627208187836426e+00 +-2.4900660030974859e+00 +7.1186184258397356e-01 +-2.7182106977424145e+00 +-7.7431162403703835e-01 +5.9164886299659303e-01 +-2.5939712922213674e+00 +-1.2189704372607801e+00 +6.1939835847320801e-01 +-2.5672528544918261e+00 +-2.5594395654342788e+00 +7.1027071368405015e-01 +-2.6281499529346317e+00 +-1.4906838084630456e+00 +6.0023496131713094e-01 +-2.3600647504815044e+00 +-1.4675014241154896e+00 +5.9976346246313461e-01 +-2.3588431603483873e+00 +-1.9563028222949386e+00 +6.6235313972462706e-01 +-2.4839735409319217e+00 +-1.0966334957251946e+00 +5.8257729712544848e-01 +-2.2808054493245624e+00 +-1.2977887949451870e+00 +6.0977960547686050e-01 +-2.4333934939778592e+00 +-1.3002058534935517e+00 +5.8711138485703229e-01 +-2.2329572319189657e+00 +-2.0087211111386827e+00 +6.7031516783753342e-01 +-2.4913691615887834e+00 +-1.0121738082295537e+00 +6.4302012896037641e-01 +-2.7466539471587983e+00 +-1.1064830706051152e+00 +5.9129700482439884e-01 +-2.3104569919934610e+00 +-2.0805165528558902e+00 +6.8500827123102848e-01 +-2.4920901954355710e+00 +-1.6952242059719356e+00 +6.6193219318193830e-01 +-2.4603018605603650e+00 +-8.9313839546252727e-01 +6.1448931273016616e-01 +-2.4063557415823298e+00 +-1.9687109114902930e+00 +6.8852622640574168e-01 +-2.4680673870249286e+00 +-1.2115673386855688e+00 +6.5417451136491800e-01 +-2.5667179849864210e+00 +-9.6839703841196700e-01 +6.3144277841220009e-01 +-2.4423977105852632e+00 +-8.6807202674650374e-01 +6.2756504793211720e-01 +-2.4777853140871073e+00 +-2.6145291358002378e+00 +7.8981676415947999e-01 +-2.8181308063485577e+00 +-8.1813177653904012e-01 +6.2597831822293293e-01 +-2.4606018428383303e+00 +-1.0071334411316026e+00 +6.7875610294321043e-01 +-2.7421357086448945e+00 +-1.1611135723413468e+00 +6.3977663416383934e-01 +-2.4221977288893131e+00 +-9.3814896578329521e-01 +6.3628396298966283e-01 +-2.4416114572373271e+00 +-7.9834528861120779e-01 +6.4222969631028004e-01 +-2.5582838520069098e+00 +-8.1495964348860217e-01 +6.5988410878952719e-01 +-2.5869253398486483e+00 +-1.0074044195428824e+00 +6.3014490960676039e-01 +-2.3400426324603485e+00 +-2.6721657663248357e+00 +7.8863610364057468e-01 +-2.6157464181392589e+00 +-1.6341729318539844e+00 +7.0919471573480419e-01 +-2.4805672996150583e+00 +-2.1030058516654062e+00 +6.1530478544728495e-01 +-1.5293580413738908e+00 +-1.0527962654364569e+00 +6.7904118790076506e-01 +-2.4124128398382418e+00 +-2.6292687643309449e+00 +8.4366108901228232e-01 +-2.8215002051261213e+00 +-2.1081127497395462e+00 +7.5473153401433735e-01 +-2.4986553380625489e+00 +-2.1081127497395462e+00 +7.5473153401433735e-01 +-2.4986553380625489e+00 +-1.9709184027613837e+00 +7.4750904777191030e-01 +-2.5108588433170125e+00 +-1.9709184027613837e+00 +7.4750904777191030e-01 +-2.5108588433170125e+00 +-2.0907533282619220e+00 +7.5177281855526135e-01 +-2.4828075252781820e+00 +-2.0762382615288302e+00 +5.8392879890294325e-01 +-1.2835432387163632e+00 +-2.0708560952844390e+00 +7.5461097026937130e-01 +-2.4995037377138987e+00 +-1.1684367129469178e+00 +7.1900935456960202e-01 +-2.6531961164892941e+00 +-2.0614325886734228e+00 +7.5563332205027411e-01 +-2.5016316262964571e+00 +-2.0521823517848259e+00 +7.5590430775998851e-01 +-2.5033862661543478e+00 +-2.0160466902961662e+00 +7.5331327767529388e-01 +-2.4892827131660362e+00 +-2.0125352767041758e+00 +7.5571705030312819e-01 +-2.5025808808930008e+00 +-1.1026513837948306e+00 +6.6160522006330247e-01 +-2.2922132075327761e+00 +-1.9840498320354392e+00 +7.6074539552753528e-01 +-2.5419665164083565e+00 +-2.0360612078255111e+00 +7.5831953594984858e-01 +-2.4854843489810783e+00 +-2.0307577902338396e+00 +7.6040204571918868e-01 +-2.4949208380727392e+00 +-2.0597468321701706e+00 +7.6306350374152043e-01 +-2.4851360057537142e+00 +-2.0947344242697210e+00 +5.9128538627511151e-01 +-1.2270755742172352e+00 +-2.0250847295685577e+00 +7.7308348870653343e-01 +-2.5035097113702025e+00 +-2.1232025850958935e+00 +6.5207353731921280e-01 +-1.6178544117971703e+00 +-1.1220040157678399e+00 +6.7633416470242069e-01 +-2.2869283724591707e+00 +-2.1224234875973682e+00 +6.5240846760344162e-01 +-1.5973992578005156e+00 +-1.9909794316423990e+00 +7.9096279354361088e-01 +-2.5472692762780356e+00 +-9.8862977533400076e-01 +7.2008110895304012e-01 +-2.4512906690167990e+00 +-1.0494515199853083e+00 +7.6070009165027552e-01 +-2.7352602059458153e+00 +-2.1761721039348418e+00 +5.8406976775372932e-01 +-1.0525874943605955e+00 +-2.0583243429170066e+00 +6.1793921765086324e-01 +-1.3269717759955724e+00 +-2.0610697102134590e+00 +6.1685119899121121e-01 +-1.3177548436022917e+00 +-2.7139945217832486e+00 +9.0751523915525023e-01 +-2.8510014666525496e+00 +-9.6698921703801866e-01 +8.1482610085989726e-01 +-2.9457098428327178e+00 +-1.1238091527118739e+00 +7.1910467747342077e-01 +-2.3891801464021736e+00 +-1.1976874541760771e+00 +7.2621893384362446e-01 +-2.3702196816708510e+00 +-1.2612582814766609e+00 +7.7148237508409989e-01 +-2.5997045755351631e+00 +-2.1613262601631162e+00 +6.0614677711167897e-01 +-1.1017373861518414e+00 +-8.9419766569313364e-01 +7.3002965426532684e-01 +-2.4585404470235939e+00 +-2.1814761360925616e+00 +5.9902950059568516e-01 +-1.0416568884977013e+00 +-1.2575002401781796e+00 +7.4993059761348624e-01 +-2.4608667467806686e+00 +-2.1857430744116946e+00 +6.0148885681447406e-01 +-1.0276755720439554e+00 +-2.1914197478602819e+00 +6.0060252867780362e-01 +-1.0147613889389584e+00 +-1.3128220138601130e+00 +8.0275117729465273e-01 +-2.5819226289501667e+00 +-1.9913428484075306e+00 +9.0054246397985971e-01 +-2.7770425417186035e+00 +-2.2382279749110014e+00 +6.2112801291131414e-01 +-9.8466861391649696e-01 +-1.1359884450479873e+00 +8.1915058437602106e-01 +-2.5317263157713668e+00 +-1.9931512046665945e+00 +9.0873327324670772e-01 +-2.5758108035222382e+00 +-1.1293926444390781e+00 +8.7611509967294721e-01 +-2.7098130766074489e+00 +-1.3312189206627232e+00 +9.0674927181670772e-01 +-2.6788448684331714e+00 +-1.1785046289831687e+00 +6.5861330086312800e-02 +-2.3465747279935592e+00 +-8.4605317188935025e-01 +5.7852117533159005e-02 +-2.5096371981888295e+00 +-1.3828566865410710e+00 +8.5591846604979996e-02 +-2.4047631254936745e+00 +-8.7650235772871632e-01 +7.5604051875894890e-02 +-2.8349189519137759e+00 +-9.9625862971004231e-01 +8.3085992165230049e-02 +-2.6425761786176896e+00 +-1.1787922632443546e+00 +9.0989898729310736e-02 +-2.3488838244759611e+00 +-9.5435075191860796e-01 +9.8731747953944071e-02 +-2.6847276681336036e+00 +-8.5262905395812283e-01 +1.2994818833245181e-01 +-2.8973678641282961e+00 +-8.9564415655129859e-01 +1.3970843400249525e-01 +-2.5059716174171283e+00 +-8.9564415655129859e-01 +1.3970843400249525e-01 +-2.5059716174171283e+00 +-1.4050640637992748e+00 +1.5673303561834959e-01 +-2.4369204964666666e+00 +-1.2237794090432994e+00 +1.5326447431208970e-01 +-2.4494755168319924e+00 +-1.3166352003837056e+00 +1.5544245715683377e-01 +-2.3594758539192418e+00 +-1.2989215989401355e+00 +1.7178967165900799e-01 +-2.3438830461801796e+00 +-1.2246080724351418e+00 +2.0335911114354002e-01 +-3.1440410135659822e+00 +-1.1120319521726076e+00 +1.8841176350897493e-01 +-2.3423917336273021e+00 +-1.1480856115537719e+00 +1.9251163992538117e-01 +-2.4924935366450685e+00 +-8.3223555707238472e-01 +1.8983664611156045e-01 +-2.9129772683587078e+00 +-1.2241293687056503e+00 +1.9789166416948756e-01 +-2.3332232190424782e+00 +-9.1207939734945809e-01 +2.0516364685921193e-01 +-2.4873321136955764e+00 +-1.4467964533412567e+00 +2.2697538755851462e-01 +-2.4182025702049543e+00 +-8.9872263672791841e-01 +2.1481107129203883e-01 +-2.5113373836620076e+00 +-1.4646546110210659e+00 +2.3633219082152213e-01 +-2.4327156199604154e+00 +-1.4646546110210659e+00 +2.3633219082152213e-01 +-2.4327156199604154e+00 +-1.1745258556274081e+00 +2.2397942576992785e-01 +-2.3234415292645973e+00 +-8.2329256964388220e-01 +2.4889601347138327e-01 +-2.7087248925211838e+00 +-1.2017224066452163e+00 +2.5829106067843838e-01 +-2.3445385377368697e+00 +-8.0239894384205157e-01 +2.7236751890470290e-01 +-2.4796015813564374e+00 +-1.1441459712885971e+00 +2.8864252459414930e-01 +-2.3841464678955764e+00 +-1.1425125068737212e+00 +2.8843347024708432e-01 +-2.3700482295564225e+00 +-1.2594727792477827e+00 +3.1144530903357825e-01 +-2.2722861886105190e+00 +-1.2429256474360690e+00 +3.2563599717541503e-01 +-2.3994294719003757e+00 +-1.2442963607555650e+00 +3.2763776801588573e-01 +-2.3728170881440320e+00 +-8.7240865683467861e-01 +3.2225618897865782e-01 +-2.5246175480101658e+00 +-1.0921080863792207e+00 +3.2707349206530328e-01 +-2.4486830365619552e+00 +-1.3127087685754992e+00 +3.2762266413862673e-01 +-2.3190475462970528e+00 +1.8529361915269682e+00 +3.8480438488051266e-01 +-4.8410155930253165e+00 +-7.1908602615747264e-01 +4.2071561605836921e-01 +-2.9174942158589463e+00 +-1.2311945264164650e+00 +4.1713816219288952e-01 +-2.5067949918852994e+00 +-1.1099644798854267e+00 +4.1740629041061394e-01 +-2.5547583108242469e+00 +-1.1929557002600932e+00 +4.3244246455617752e-01 +-2.5281349667043345e+00 +-2.0019614049695611e+00 +3.9155236647992009e-01 +-1.3310627106006376e+00 +-2.0070709240255620e+00 +3.9184957560545813e-01 +-1.3196073906933234e+00 +-1.1433927586582049e+00 +4.5741199529494359e-01 +-2.3924366056723119e+00 +-1.9532872376804880e+00 +4.2229226749803705e-01 +-1.4037908006676607e+00 +-1.1814495262345723e+00 +4.8051753604043035e-01 +-2.5542038269078975e+00 +-1.1814495262345723e+00 +4.8051753604043035e-01 +-2.5542038269078975e+00 +-1.2461143492930753e+00 +3.7664607548576762e-01 +-1.3774979015796689e+00 +-1.9658271957645934e+00 +4.2508958646363948e-01 +-1.3482072767374118e+00 +-1.4541180949124457e+00 +4.6530431019013802e-01 +-2.1786379496244694e+00 +-1.3375768521342832e+00 +5.0364130173726429e-01 +-2.4905119502336639e+00 +-1.0863652729152777e+00 +4.9184739792625143e-01 +-2.3829127313851344e+00 +-1.2944475396775446e+00 +5.5227146645571323e-01 +-2.7869577884498775e+00 +-1.1484854165117595e+00 +4.9469147806339570e-01 +-2.2750725221578754e+00 +-7.4139353690550858e-01 +5.5961493223488123e-01 +-2.8966196801172899e+00 +-2.1276416238899141e+00 +5.7246604198637407e-01 +-2.4705475577899616e+00 +-2.0516286607577965e+00 +4.5790313858547138e-01 +-1.2155596143080187e+00 +-5.0646347614603793e-01 +7.2953273883666847e-01 +-4.6329840674434504e+00 +-2.0881724305791627e+00 +4.4707442924095747e-01 +-1.0356399255887541e+00 +-7.1840848466567864e-01 +5.7584986858027576e-01 +-2.7528346256910954e+00 +-9.2673193048350241e-02 +6.4196420985869496e-01 +-3.6961536554502081e+00 +-1.2289987163881337e+00 +5.9948050870549574e-01 +-2.5591223861658392e+00 +-1.5412940524899950e+00 +5.9405047717489845e-01 +-2.3579595874401291e+00 +-1.6723568409450755e+00 +6.3201721062527816e-01 +-2.4897750379006176e+00 +-1.1745697304666296e+00 +4.7280016020522103e-01 +-1.4068827851847183e+00 +-2.5470993948043308e+00 +7.0411740672561063e-01 +-2.5959618243543878e+00 +-1.9478678668286002e+00 +6.5584885080085065e-01 +-2.4858697479954861e+00 +-1.2146824310246747e+00 +6.2336599640510437e-01 +-2.5686186526283761e+00 +-7.5924277280702013e-01 +6.2439132472564884e-01 +-2.6420502562471628e+00 +-1.6428476941648640e+00 +6.5959634155468405e-01 +-2.4639314764796931e+00 +-2.1242941071680153e+00 +5.1864910755164051e-01 +-1.0795336870129857e+00 +-2.1313382867773889e+00 +5.1551144679068373e-01 +-1.0505622946976374e+00 +-2.1313382867773889e+00 +5.1551144679068373e-01 +-1.0505622946976374e+00 +-1.9729932900383986e+00 +6.9131272405209798e-01 +-2.4906403274201945e+00 +-1.2681385649040335e+00 +6.5642733132103581e-01 +-2.5553233063661320e+00 +-1.2681385649040335e+00 +6.5642733132103581e-01 +-2.5553233063661320e+00 +-8.8483056903963153e-01 +6.3441965619998741e-01 +-2.5262299931984513e+00 +-2.5710530317598863e+00 +7.8838746114104419e-01 +-2.8468849229349940e+00 +-2.5172012146686180e+00 +7.5597736992091591e-01 +-2.6657496478639491e+00 +-1.0940213548038555e+00 +6.3638272495208970e-01 +-2.3600269674709211e+00 +-1.0613422941682058e+00 +6.7827912105390742e-01 +-2.7006112065852452e+00 +-1.1919468309235921e+00 +6.5513880317468820e-01 +-2.4088419936533154e+00 +-1.1472854822708953e+00 +6.8862051304575156e-01 +-2.6336575503379742e+00 +-2.5819237492296265e+00 +8.2488164167162903e-01 +-2.8537532295278925e+00 +-1.3046244291674649e+00 +6.9067484524398837e-01 +-2.4375972477086592e+00 +-1.3443579962713526e+00 +7.0519637026290982e-01 +-2.5612214248820639e+00 +-1.1703972948703394e+00 +7.0730353995499651e-01 +-2.6062518410262725e+00 +-2.0065987850370570e+00 +7.6234981644546418e-01 +-2.5325961954189049e+00 +-7.9645881140012864e-01 +7.0214741457840946e-01 +-2.5577195647115660e+00 +-1.4789919200926189e+00 +7.4541007151080108e-01 +-2.5472262485341539e+00 +-1.0010888160716982e+00 +7.1172548245211942e-01 +-2.4414468504698865e+00 +-1.2576611338056582e+00 +6.9358685709987478e-01 +-2.2545047265438751e+00 +-1.2422216852569647e+00 +7.7795553866811429e-01 +-2.6010420613039709e+00 +-2.1702780807674840e+00 +6.0783660525054983e-01 +-1.0808027062398140e+00 +-9.9505265459917847e-01 +7.2990658572220035e-01 +-2.3821261878217488e+00 +-2.2317409060630506e+00 +6.0711039645970921e-01 +-1.0083157470914708e+00 +-1.9987790476947471e+00 +9.3133798197727258e-01 +-2.8091781412435468e+00 +-2.0040986634922437e+00 +9.0820709319540571e-01 +-2.5862379358073224e+00 +-1.2376909689137603e+00 +9.4364174523760069e-01 +-2.7316856531427365e+00 +-1.0889894063707115e+00 +6.8035598018317811e-01 +-2.4174396283244803e+00 +-1.4683784596614415e+00 +2.9028834957312616e-01 +-2.3956414012575591e+00 +1.4161781271429474e+00 +1.3467780849630021e-01 +-3.8430582541377127e+00 +-1.0724683686408065e+00 +5.1013911295735315e-01 +-2.4047477824051473e+00 +-1.0675481693140492e+00 +7.2277112311811609e-01 +-2.4490055595206495e+00 +-1.4764855535520494e+00 +1.0297080807350663e-01 +-2.3921743396811945e+00 +-1.1820743209876949e+00 +1.4165343921713178e-01 +-2.3457011677958435e+00 +-1.4598545545457826e+00 +1.9569812012786075e-01 +-2.3880656855361329e+00 +-1.2825739911423764e+00 +3.9849376471861564e-01 +-2.3507729221156080e+00 +-1.4002915464328443e+00 +7.0417424589988398e-01 +-2.3894073361780253e+00 +-1.1970334627339394e+00 +1.5042718859642052e-02 +-2.3693225024172055e+00 +-1.2208251699740087e+00 +7.6180942358568191e-02 +-2.3208777017603195e+00 +-1.5271013848337287e+00 +2.0909152635339015e-01 +-2.3865943869728912e+00 +-1.4663763555929483e+00 +2.0707905405234822e-01 +-2.3692432111037629e+00 +-9.6094020850210315e-01 +6.5176146418537140e-01 +-2.4012334608935704e+00 +-1.5010399951082396e+00 +2.1178380829616525e-01 +-2.3852902505883482e+00 +-9.6738087004048157e-01 +6.6837552184852245e-01 +-2.4524898541960600e+00 +-9.8045118481065274e-01 +6.7041406632346634e-01 +-2.4426151864189385e+00 +-1.1178862891173289e+00 +7.3447065647675958e-01 +-2.4123307371658411e+00 +-1.2836162326786549e+00 +5.0622405898516777e-02 +-2.2344291983781503e+00 +-1.1700115709148682e+00 +5.1452422637721713e-02 +-2.3602011052934322e+00 +-1.4423184787924883e+00 +1.8616076331828207e-01 +-2.3814534094162330e+00 +-1.3036520878007136e+00 +2.2130098621278935e-01 +-2.4175168704051386e+00 +-1.2966619338609460e+00 +2.2076529967502542e-01 +-2.4005105532919169e+00 +1.2798889397601727e+00 +2.3133005375374807e-01 +-3.6419062103587554e+00 +-1.4098813924735285e+00 +6.3586050755953927e-01 +-2.3095116990279596e+00 +-1.2332164481398356e+00 +6.2108380461075785e-01 +-2.3443316769986260e+00 +-1.0893356956401752e+00 +6.0432408190863551e-01 +-2.3768630271051219e+00 +-1.0122636428467111e+00 +6.0888528437043599e-01 +-2.4263368244834180e+00 +-9.7653887556382479e-01 +6.1026536805681852e-01 +-2.4389784843699784e+00 +-1.2956539139041467e+00 +7.2879718406789062e-01 +-2.4562017304925226e+00 +-9.9788449586775363e-01 +7.2061199878182525e-01 +-2.4434311073858868e+00 +-1.5279031050583376e+00 +2.2067595841414187e-01 +-2.3959360624650690e+00 +-1.3224655821753399e+00 +2.3558847600989838e-01 +-2.3853339614226790e+00 +-1.3074947756287016e+00 +2.3218795987891391e-01 +-2.3718596251194675e+00 +-1.0724924900307065e+00 +2.1731336822649092e-01 +-2.4281973882203527e+00 +-1.0724924900307065e+00 +2.1731336822649092e-01 +-2.4281973882203527e+00 +-1.1204144783335421e+00 +2.5936710259783963e-01 +-2.3770307180262051e+00 +-1.5271350203875249e+00 +4.1878759013670275e-01 +-2.4288359291784527e+00 +-1.3266706232062413e+00 +5.6516877572156810e-01 +-2.4343384022921248e+00 +-1.4214548115115853e+00 +5.9569551764255280e-01 +-2.3054115297844575e+00 +-1.2397426119237476e+00 +6.3325378629258733e-01 +-2.3737706059242631e+00 +-1.3115228843478910e+00 +9.7475793181601975e-02 +-2.3887715464615500e+00 +-1.2393746179609215e+00 +1.0986212266174560e-01 +-2.3148942490869744e+00 +-1.4346848988151006e+00 +1.9352735526526571e-01 +-2.3827595352749573e+00 +-1.3098681454194951e+00 +4.4387050287030549e-01 +-2.3742945477027870e+00 +-1.1532232171469552e+00 +4.3912494891731430e-01 +-2.4379576803098666e+00 +-1.3118277917443883e+00 +5.9803954200659593e-01 +-2.3761621736194232e+00 +-1.1203933042812020e+00 +5.9682005733760457e-01 +-2.3616217306680642e+00 +-1.1075517441231091e+00 +5.9414334958224901e-01 +-2.3239540517535380e+00 +-1.2359536777770450e+00 +7.1200845200473295e-01 +-2.3483023013263891e+00 +-1.2359536777770450e+00 +7.1200845200473295e-01 +-2.3483023013263891e+00 +-1.0702042428653027e+00 +7.1713351638110678e-01 +-2.4491236209807417e+00 +-1.1306140334252393e+00 +7.3632678784286454e-01 +-2.4158103761389023e+00 +-1.1375143347534822e+00 +7.2680239388836698e-01 +-2.3486780336148403e+00 +-1.3677006035468944e+00 +2.1328784556528413e-01 +-2.3962446015858370e+00 +-1.3213330943019135e+00 +5.1891769352940886e-01 +-2.4368607602109820e+00 +-1.3947442992194432e+00 +6.3977104966231324e-01 +-2.3376452690371585e+00 +-1.2991871152593799e+00 +7.1034964062045924e-01 +-2.4022053245451946e+00 +-1.2764642436168290e+00 +7.3969864633702787e-01 +-2.4670191229882565e+00 +-1.2288341863686820e+00 +2.1070910276435756e-01 +-2.4013336108958385e+00 +-1.1859480294734226e+00 +6.1589011913266045e-01 +-2.3159464659887981e+00 +-1.1601805594045977e+00 +7.3537239237764118e-01 +-2.3981303755230723e+00 +1.3478393844021992e+00 +1.2780980529034125e-01 +-2.4360228926160006e+00 +1.7421963603886363e+00 +3.5397073478610946e-01 +-4.6049298594455568e+00 +4.1036191191172557e+00 +-8.5512532642151681e-02 +-7.7978074048554840e+00 +4.6125138920246433e+00 +-9.0549353817792000e-02 +-8.6801601830649791e+00 +1.3530221729405052e+00 +2.1791182222383676e-01 +-2.4244245552413397e+00 +7.9675038861482417e+00 +2.0875865830645857e-01 +-1.3857577117134532e+01 +4.5793899669845333e+00 +-1.2939174770845316e-01 +-8.6074243032831586e+00 +4.7116474697455528e+00 +-1.1538225649384645e-01 +-8.7533147273431133e+00 +1.8477807811179110e+00 +2.7682392552603502e-01 +-4.3874496434171730e+00 +2.0104053343416961e+00 +5.2733083625954225e-01 +-2.7262791622199738e+00 +-2.6236500642006866e-01 +6.1340737594286676e-01 +-3.5696851568965440e+00 +-1.2378291099289707e-01 +7.2103977600532942e-01 +-3.7036339966016261e+00 +-1.0693843037484589e+00 +7.5545569874444629e-01 +-2.4932309047740788e+00 +-4.6299016648696451e-03 +4.7071847833544628e-01 +-3.3446350602392902e+00 +-1.1877093746887393e+00 +7.2393360841560628e-01 +-2.5657775170521315e+00 +-1.0021724556519422e+00 +1.3433237844606802e-01 +-2.4714065998913783e+00 +1.6493476795651079e+00 +2.3603650417086411e-01 +-2.6609173305210088e+00 +1.5336152797476239e+00 +3.4634497017752264e-01 +-2.5855555591597628e+00 +-1.8701940686966543e-02 +5.6479003336663136e-01 +-3.5661581349264617e+00 +-7.8697427962865119e-01 +5.6598392577648227e-01 +-2.6090320291090339e+00 +-1.2555519747882007e+00 +8.1770111995738060e-01 +-2.4005821447497446e+00 +1.6669150288159118e+00 +2.3466508855451689e-02 +-2.2159778166112334e+00 +1.6489269676706682e+00 +1.1630303508010759e-01 +-2.6613249840332136e+00 +-9.9848502918073989e-01 +2.3572536874384839e-01 +-2.3759693627469898e+00 +-9.2842420945102255e-01 +4.5197657910150441e-01 +-2.5410972071787978e+00 +-1.1683089086037619e+00 +4.5392230117850346e-01 +-2.3839749888125512e+00 +-7.7486480706142258e-01 +5.3815482063269882e-01 +-2.7334858505549202e+00 +-1.0700685655434117e-01 +3.3739897724783974e-01 +-7.5701725395821318e-01 +-1.2923711726526046e+00 +5.2870251971077120e-01 +-2.3617696630496310e+00 +-1.2946821560354052e+00 +7.7255891858128389e-01 +-2.3806462558745443e+00 +-1.0415199782428661e+00 +1.2327822286120065e-01 +-2.4659830183655989e+00 +-1.0415199782428661e+00 +1.2327822286120065e-01 +-2.4659830183655989e+00 +-1.0027998791304025e+00 +1.7970990619802762e-01 +-2.3179718368951687e+00 +-7.9853441995919339e-01 +2.2249882389852113e-01 +-2.4766522155526007e+00 +-1.0923626681624261e+00 +2.4367444355123430e-01 +-2.5146695584206680e+00 +-1.0923626681624261e+00 +2.4367444355123430e-01 +-2.5146695584206680e+00 +1.6271945991148846e+00 +3.0162789104027676e-01 +-2.2458275984428484e+00 +1.6638193866224642e+00 +3.4724511729652785e-01 +-2.4439194415572638e+00 +-6.7060828385738724e-01 +3.8019497284580067e-01 +-2.9424499420894330e+00 +1.8776159588992243e+00 +4.1515162418636953e-01 +-2.8428977556083024e+00 +1.5757430092143335e-01 +4.1579322874203750e-01 +-2.7629535364234594e+00 +-8.9540665316899345e-02 +3.3101987401656374e-01 +-7.1089291304696545e-01 +-8.7436438268156724e-01 +5.5458512150044470e-01 +-2.4602826620456031e+00 +-1.1444417093907537e+00 +7.3921197896141189e-01 +-2.5232890315780869e+00 +-9.2421722866640899e-01 +1.1260115866760156e-01 +-2.5280256693727812e+00 +-9.2530713313583624e-01 +1.1159857439145068e-01 +-2.5130264111233971e+00 +-8.0169255440359377e-01 +1.2243477091045686e-01 +-2.6108524698229205e+00 +1.4237132047167083e+00 +1.1836322020039640e-01 +-2.2845118117465795e+00 +1.3789990345548706e+00 +1.1661161436094923e-01 +-2.3534506998694500e+00 +1.6421312279858227e+00 +1.8450206412982445e-01 +-2.1662810879029228e+00 +1.5481379692963118e+00 +1.8534472350383344e-01 +-2.2230869848259518e+00 +-9.3792980974523021e-01 +2.0903337585249321e-01 +-1.6432621065732176e+00 +-6.3273549450096922e-01 +3.5100528062654685e-01 +-3.0299200080101114e+00 +1.6967697829931083e+00 +3.6292844037420635e-01 +-2.5482742458652372e+00 +1.8959342253293550e+00 +4.5471239091332921e-01 +-3.0492155880890914e+00 +-2.9979723061190616e-01 +4.8570607356484791e-01 +-3.7169279406265039e+00 +7.3894249486757962e-02 +5.0559981999835957e-01 +-3.2424938798669904e+00 +-1.0413765782512432e+00 +3.0135886173232751e-01 +-9.0765062411649089e-01 +7.2462383987185533e-02 +5.5710089467803625e-01 +-2.9572137162285328e+00 +-1.9989410953867429e-01 +6.5518678889880022e-01 +-3.5875437253778339e+00 +-8.8902082427465001e-01 +6.2959247399447538e-01 +-2.5788143949793785e+00 +-1.2471269807014387e+00 +6.0076672438201695e-01 +-2.4371142345640853e+00 +-1.0106153838901422e+00 +6.6318369146716094e-01 +-2.5437992735073256e+00 +-1.0106153838901422e+00 +6.6318369146716094e-01 +-2.5437992735073256e+00 +-1.2424442589815479e+00 +6.5571777875252446e-01 +-2.3508015842558749e+00 +-1.3973764020566948e+00 +7.1699885813942132e-01 +-2.6791222617945460e+00 +-1.1138902081031594e+00 +6.9704296662064763e-02 +-1.1475760306614837e+00 +-1.1097121222577728e+00 +6.9698181445949234e-02 +-1.1700312170576082e+00 +1.6575086405901125e+00 +5.2203595152456586e-03 +-2.3194946472356288e+00 +-8.8166956530105145e-01 +4.9732529726277612e-02 +-2.3344912281852483e+00 +-1.0083617539628722e+00 +5.1150075425068484e-02 +-2.4574913685135060e+00 +-1.0636590549362448e+00 +1.0185037544821010e-01 +-2.4559888384210300e+00 +-8.2628935418410920e-01 +1.4799903682472493e-01 +-2.5989577106448958e+00 +-9.9223371521471948e-01 +1.5480914923500497e-01 +-2.4685452795700242e+00 +-1.0269904335191895e+00 +1.7612616013511731e-01 +-2.4497003207050123e+00 +-1.1235920077026986e+00 +1.9280834321577953e-01 +-2.4576779280559840e+00 +1.3388685513654359e+00 +2.1117709579976759e-01 +-2.3343616223986308e+00 +1.4310935419245321e+00 +2.1233040386252319e-01 +-2.2642268936173622e+00 +-8.2400641450169809e-01 +2.2730957106615443e-01 +-2.5744090675252833e+00 +-8.6073251025462183e-01 +2.3028800600770313e-01 +-2.5385748985239869e+00 +-7.3203149880168417e-01 +2.5589999957157367e-01 +-2.6941034591638444e+00 +-8.2390096762976972e-01 +2.5882001974828989e-01 +-2.5820153624371933e+00 +-8.2325347608760724e-01 +2.5818965401171523e-01 +-2.5931937018919355e+00 +1.3905871572847199e+00 +2.7251023681312586e-01 +-2.2865849120017812e+00 +1.3120072588562608e+00 +2.9256708945526871e-01 +-2.3238273143978212e+00 +1.3120072588562608e+00 +2.9256708945526871e-01 +-2.3238273143978212e+00 +1.3788539254091798e+00 +2.9328735965834479e-01 +-2.2974562056347443e+00 +-8.3225434968032852e-01 +3.1188603915749391e-01 +-2.4915876787271367e+00 +-3.8215488423033361e-01 +4.3866550840449198e-01 +-3.9985534014838366e+00 +-1.1083266499233997e+00 +3.3883991119445889e-01 +-2.3910663839765141e+00 +-3.8081956188255150e-01 +4.7278837319469219e-01 +-4.0068222788793495e+00 +2.0129801849588061e-01 +5.2053953530097952e-01 +-3.0427862620967718e+00 +-1.2035155015735048e+00 +4.6324088540632130e-01 +-2.4940682243849239e+00 +-1.2003403440651459e+00 +4.5415370421947338e-01 +-2.4106900660844950e+00 +-1.2475087363942272e+00 +4.6211793608081253e-01 +-2.4210373792130877e+00 +-1.2475087363942272e+00 +4.6211793608081253e-01 +-2.4210373792130877e+00 +3.1194901835149685e-01 +5.6856303766135319e-01 +-3.0609764577589056e+00 +-1.2655327499051681e+00 +4.9250189548135292e-01 +-2.4075096315881446e+00 +-7.2392277907541192e-01 +6.5694743025428104e-01 +-2.8274506456356225e+00 +-1.3391311783781035e+00 +6.0929430366052750e-01 +-2.4022623472125666e+00 +-8.3289534068781645e-01 +6.5291748021242790e-01 +-2.6091785760409509e+00 +-8.4240617368490833e-01 +7.0119304468106058e-01 +-2.5906549081939598e+00 +-8.8236019025838508e-01 +6.7802514916513612e-01 +-2.4280045642733437e+00 +-1.0481525746021292e+00 +7.1157209606686456e-01 +-2.5796080974263100e+00 +-1.2426735186691253e+00 +6.8149533326967604e-01 +-2.3494339483410482e+00 +-1.3143315985984783e+00 +7.1016340738680561e-01 +-2.3248155569479954e+00 +-7.7308607969398724e-01 +6.3499651374937766e-02 +-2.3175141654323399e+00 +-8.5745923427470283e-01 +6.2696846398127101e-02 +-2.5409710034100579e+00 +-9.1720079201896731e-01 +6.6089976041853307e-02 +-2.3877877927126163e+00 +-1.1205722802515889e+00 +7.0732045341041966e-02 +-2.4430911837821090e+00 +1.0863864460012549e+00 +4.9577643939476668e-02 +-2.0426456588125190e+00 +-8.2908213402582143e-01 +8.7745068920390343e-02 +-2.4849006186178464e+00 +8.9659059858313656e-02 +1.3333632897225789e-01 +-2.4481596824636145e+00 +-1.1348278046028308e-01 +1.4734205493754279e-01 +-6.8179999634920085e-01 +-1.1348278046028308e-01 +1.4734205493754279e-01 +-6.8179999634920085e-01 +-8.7216640237791332e-01 +1.8530550070099444e-01 +-2.5413783746217948e+00 +1.1678741724040314e+00 +1.8603253431072930e-01 +-2.2863843687364120e+00 +8.6119683700011621e-02 +2.1528601862690686e-01 +-2.5269900326145298e+00 +-2.6825909277960036e-01 +2.5143711366671473e-01 +-3.6484073199873506e+00 +-1.0190823912936298e+00 +2.2944071213837189e-01 +-2.4870435411578220e+00 +-7.9504104416242161e-01 +2.7182133871698805e-01 +-2.5427363836802570e+00 +1.3371020814452745e+00 +2.8949497419607045e-01 +-2.4709624964911967e+00 +-5.2193916633465953e-01 +3.2863775894032488e-01 +-3.6282667929415000e+00 +1.9353527307926015e+00 +2.9325919261171307e-01 +-2.3325056903888681e+00 +-1.3295749440150026e-01 +2.0742131334817746e-01 +-7.1896551920226559e-01 +-4.2163112821296783e-01 +3.6220766637700019e-01 +-4.1101661402622023e+00 +-3.9534199512347173e-01 +3.5555668699298476e-01 +-3.8194345147111712e+00 +1.4240493315242178e+00 +3.1663152079028700e-01 +-2.3582855194114813e+00 +2.9732700445134780e-01 +3.2249638390089247e-01 +-2.6218219249957131e+00 +2.0358575055475394e+00 +3.5698724876864885e-01 +-2.4626685860948276e+00 +-7.6103517500901718e-01 +3.5544451748066824e-01 +-2.6657235621443793e+00 +-8.2150940070873457e-01 +3.6574805830447232e-01 +-2.5508980458450337e+00 +-8.2150940070873457e-01 +3.6574805830447232e-01 +-2.5508980458450337e+00 +-1.3452439799411905e-01 +4.3582452362099566e-01 +-3.4034199577901529e+00 +-7.3008860132935327e-01 +3.8438888402404914e-01 +-2.6856700541391754e+00 +-8.6218245215007172e-01 +3.7685409037772022e-01 +-2.4699852107138178e+00 +-1.9551377263003866e-01 +4.7672211113605734e-01 +-3.5944709745584591e+00 +2.2663197036739377e-01 +4.3669192326495981e-01 +-2.7070724233545871e+00 +-3.7404387745758028e-01 +5.8851900589848305e-01 +-4.4721324225345329e+00 +-8.3392036769187206e-01 +4.4426022594660664e-01 +-2.6674491512176370e+00 +-8.3710261249870233e-01 +4.3167089561141647e-01 +-2.5544921504880591e+00 +-8.3520691542497216e-01 +4.7145498430364918e-01 +-2.5572060691701624e+00 +-1.1096719370240941e-01 +5.8786693082768315e-01 +-3.6504230734528189e+00 +-9.2201671472535640e-01 +4.4945987283256644e-01 +-2.3884108628540424e+00 +-3.0536414111660282e-01 +6.1294762676541625e-01 +-3.8789147161909501e+00 +-9.6540682859685290e-01 +4.5141810996367443e-01 +-2.3091116490637367e+00 +3.4510174951083467e-01 +5.5039131742013614e-01 +-2.9703683304833133e+00 +-8.0111262062005473e-01 +5.0616693584399075e-01 +-2.6437663284705626e+00 +-1.1650705529042995e+00 +5.0530182598518669e-01 +-2.3725229229364992e+00 +-1.1923430526932450e+00 +5.1176078884321796e-01 +-2.3851556490920052e+00 +-1.2123764971824700e+00 +5.1213653186913566e-01 +-2.3878555091504103e+00 +-1.2318946636934687e+00 +5.1246918911395389e-01 +-2.3892994917809753e+00 +-1.2526731760915764e+00 +5.1207252823661142e-01 +-2.3906872582701153e+00 +-1.2650891932134962e+00 +5.0556912116154729e-01 +-2.3796289018070893e+00 +-8.5026957670504011e-01 +5.9954731599457556e-01 +-2.6695096973630550e+00 +-7.6037931848052065e-01 +6.4269716232713658e-01 +-2.6489810262725646e+00 +-7.8436043323266635e-01 +6.4580917161848073e-01 +-2.6422107060417264e+00 +-8.6156791012609735e-01 +6.9946105023556582e-01 +-2.7148805841435020e+00 +-8.3810282645286849e-01 +6.9161630743587865e-01 +-2.7121108419403872e+00 +-9.3486074475201375e-01 +6.6441366008961322e-01 +-2.4279105491140958e+00 +-9.7868159820971146e-01 +6.9937567732715367e-01 +-2.5943908171321284e+00 +-1.1304794474603901e+00 +8.8601198261450209e-01 +-2.6817481312502505e+00 +-3.6968235951235529e-01 +-9.6462066849371982e-03 +-6.6797490816974203e-01 +-1.1196783260670260e+00 +4.2660076782263447e-02 +-1.1309644353687276e+00 +-4.3249443040684060e-01 +4.9632131692526546e-02 +-6.6082225656626570e-01 +1.4657760490283900e+00 +-4.1736064148395639e-02 +-2.1837340229154441e+00 +1.0507412354466597e-01 +6.9479405011676635e-03 +-2.4946837041746943e+00 +-1.4321405856772024e-01 +7.8136355918159026e-02 +-7.0912758031381140e-01 +2.9117398068662481e-01 +3.6401220003252417e-02 +-2.6241464721576859e+00 +-8.3747930423154560e-01 +6.5142856149975406e-02 +-2.4948085155025890e+00 +-7.8794612476412773e-01 +8.7292003879240021e-02 +-2.5686863960166444e+00 +-1.0974336397190356e+00 +9.4155004881387658e-02 +-2.4730043979966396e+00 +-7.7680704500920683e-02 +1.0668613123302541e-01 +-6.5898745328749364e-01 +-7.8500277641163774e-01 +1.6189313559270008e-01 +-2.5650428441782291e+00 +2.0812544941257238e+00 +1.5546858500439500e-01 +-2.3838877132322391e+00 +2.9561663535953586e-01 +1.6998940265341905e-01 +-2.6288802286691411e+00 +-1.1118618394936868e+00 +1.7771260099342778e-01 +-2.3828271796163460e+00 +1.3528655314833620e+00 +1.6780161328432530e-01 +-2.3211322049294458e+00 +-8.8749436396905856e-01 +1.9445633323215669e-01 +-2.3944064710166297e+00 +-1.0425973712549936e+00 +2.0281366327339195e-01 +-2.4051416464343411e+00 +-7.7820819222542803e-01 +2.2239446900902615e-01 +-2.6137500902173967e+00 +-7.2711026418424540e-01 +2.8906079989040917e-01 +-2.7457201083499814e+00 +-9.4182842172589509e-01 +2.9319388416303116e-01 +-2.3764426945266615e+00 +2.7517461316800285e-01 +3.1582285212739092e-01 +-2.6165940725786929e+00 +-4.4794218943965358e-01 +4.2970195592836319e-01 +-4.1887276326897362e+00 +-4.0740645534997827e-01 +4.3464804407274366e-01 +-4.0838983953112491e+00 +8.5679065018402556e-01 +3.9703527455862997e-01 +-3.1398816553081219e+00 +-1.6490166554948194e-01 +2.4198719537691682e-01 +-6.9864344776018483e-01 +-4.5923077721044542e-01 +5.1683097478622997e-01 +-4.1945206441505603e+00 +-4.5918996799361189e-01 +5.1347418083675178e-01 +-4.1806505202023310e+00 +-9.4236970488092497e-01 +3.8425873218466589e-01 +-2.4719256720828517e+00 +-3.7593918610772581e-01 +4.9150641298643688e-01 +-3.7406537525531935e+00 +2.1281641759017451e+00 +4.8565350573003208e-01 +-2.8775625651978047e+00 +-1.2876945538934936e+00 +4.2585216238865103e-01 +-2.4786776855174502e+00 +-1.3662050887870527e+00 +4.1786680712528290e-01 +-2.3986604477886466e+00 +-1.1886133028824171e-01 +5.2835798202489748e-01 +-3.4817199325751016e+00 +-7.4342304550911642e-01 +4.5496718220397853e-01 +-2.7296551078272060e+00 +-7.5505007025017801e-01 +5.7581896469460436e-01 +-2.7017565803683321e+00 +-8.1770210443824887e-01 +5.7874502096217151e-01 +-2.5815484459151756e+00 +-6.9386081140656730e-01 +6.5136913020253018e-01 +-2.9657554610120931e+00 +-9.1456180589299618e-01 +5.6899153078183551e-01 +-2.3892088841228487e+00 +-9.9475939743099129e-01 +6.4245104077249071e-01 +-2.3537609806592892e+00 +-1.1332136847572010e+00 +6.5830555703166072e-01 +-2.3381755088302851e+00 +-1.1576086578040825e+00 +6.9516563880833593e-01 +-2.2370657692050258e+00 +-1.1517843374370971e+00 +8.9925849084228437e-01 +-2.4442361512122339e+00 +-1.1215542655090225e+00 +-2.4308805514652306e-02 +-2.4617747446588067e+00 +-4.2379508964570889e-01 +4.0728908934395354e-02 +-6.5411013706770715e-01 +-1.1014215110465615e+00 +7.1078018607003704e-02 +-1.1713965123342860e+00 +-1.1014215110465615e+00 +7.1078018607003704e-02 +-1.1713965123342860e+00 +-6.8436236055892968e-02 +8.9906799532120149e-02 +-6.5412208900305957e-01 +2.1733824616369762e-01 +7.3444482908291281e-02 +-2.5919783958108531e+00 +-1.3243141539706269e-01 +1.0842718989466549e-01 +-6.9772074364818937e-01 +1.6583424886882232e+00 +1.0257075101468943e-01 +-2.1855975059054806e+00 +1.0193086579069809e-01 +1.1976376369614881e-01 +-2.5986013453220385e+00 +1.9727290527964787e+00 +1.0381447585277472e-01 +-3.0200928021552391e+00 +-7.9386750418970486e-01 +1.4603554173887137e-01 +-2.4085585151801343e+00 +-7.9191042785190235e-01 +1.4743006748493087e-01 +-2.4929143142318964e+00 +-7.5120072770675772e-01 +1.6158523800630689e-01 +-2.8326523576160025e+00 +2.0967166858302879e-02 +1.6186431236818766e-01 +-2.4588789014696157e+00 +-1.0672459893341543e-01 +1.4205403355524540e-01 +-6.7949851964305907e-01 +-1.0672459893341543e-01 +1.4205403355524540e-01 +-6.7949851964305907e-01 +-7.7379151851617992e-02 +1.4994905374549017e-01 +-6.6587987719977171e-01 +-7.3294546501663826e-01 +1.8544941005123727e-01 +-2.6192457717096844e+00 +1.3326845455236709e+00 +1.8113292917107451e-01 +-2.3907982966003618e+00 +-1.2208030645673792e-01 +1.5417231701738304e-01 +-6.9022934547278592e-01 +-1.2912940839299164e-01 +1.5787771141537738e-01 +-7.0509418937752866e-01 +-1.2932942518796586e-01 +1.5790608813949503e-01 +-7.0455255445340215e-01 +4.8838766587942462e-01 +2.0222019338629374e-01 +-2.6020834614507025e+00 +-1.0169190951830924e+00 +2.0286995750443446e-01 +-2.4314757518305989e+00 +-8.5147091001012765e-01 +2.1180773921999280e-01 +-2.4131071222164624e+00 +-1.0349911848979383e+00 +2.1947388339103804e-01 +-2.3718846713489672e+00 +-7.3516730716053480e-01 +2.9792949222078469e-01 +-2.6928531230341242e+00 +-7.4674752461500782e-01 +2.9801084348829049e-01 +-2.6749204406610190e+00 +2.0473599963461022e+00 +3.1046854956954534e-01 +-2.5275670685734255e+00 +-1.1206973861198433e+00 +3.1740303952624838e-01 +-2.4441505744210406e+00 +-6.4612317961541632e-01 +3.6192524921368502e-01 +-2.9635853317479310e+00 +-1.1631252676374997e-01 +3.9672950076306224e-01 +-3.3963088502023489e+00 +-1.3425785616025160e-01 +3.8630363638431869e-01 +-3.2746040079791672e+00 +-4.4694615336672905e-01 +4.7773421044661951e-01 +-4.1956199483515464e+00 +2.1025052542899427e+00 +4.2333127913907109e-01 +-2.7937115451460675e+00 +-4.0317216009428819e-01 +4.8083989309656533e-01 +-4.0846437392781416e+00 +1.4811414035429210e-01 +3.9652985602624347e-01 +-2.6290924540667544e+00 +1.9771264379226268e+00 +4.3648199346409039e-01 +-2.8748370903241995e+00 +-4.6742598096581206e-01 +5.0310080534789903e-01 +-4.2522282462099703e+00 +-7.1874799611559137e-01 +4.0068288217533804e-01 +-2.7773793222444505e+00 +-1.4883572844835749e-01 +2.6344635686282952e-01 +-7.0286228454657818e-01 +-4.1713684027035125e-01 +5.1702279949715313e-01 +-4.2324469991824101e+00 +-9.0130559546825073e-01 +3.9145150125451855e-01 +-2.5645196037643783e+00 +-3.9216413449304394e-01 +5.0125727315364077e-01 +-3.9182339277537301e+00 +-9.7780475034308867e-01 +3.8709040821470364e-01 +-2.4472012225732178e+00 +-4.6709392965707969e-01 +5.3352618156777654e-01 +-4.2108924280584796e+00 +1.4285181493746926e-01 +4.3600448131449721e-01 +-2.8160039867716971e+00 +1.4285181493746926e-01 +4.3600448131449721e-01 +-2.8160039867716971e+00 +-3.4437403188994359e-01 +4.8495638605910474e-01 +-3.5698988313744349e+00 +-1.1300910968712907e+00 +3.9140423153174847e-01 +-2.3893607251152300e+00 +-4.2548204328672784e-01 +5.3736083707636673e-01 +-4.1224455308308245e+00 +-3.7282033654353075e-01 +5.3641141400300651e-01 +-4.0002756880066093e+00 +-3.8059731720266282e-01 +5.4224042186308929e-01 +-4.0591296642021977e+00 +-2.6478744547067812e-01 +5.1846091681915973e-01 +-3.6971676904643389e+00 +-2.7703672795885914e-01 +5.2745784435940302e-01 +-3.7140631373906605e+00 +-3.7172997955720621e-01 +5.5805494811862288e-01 +-4.0028718388972973e+00 +-3.4893896396811469e-01 +5.6471647900107935e-01 +-3.9263906821450405e+00 +-1.1416780678834060e+00 +4.3388296882933569e-01 +-2.3758455083851717e+00 +-2.0131070327248216e-01 +6.0940783980244129e-01 +-3.7233578625314681e+00 +1.2711161152674583e-01 +5.6041570872179192e-01 +-3.0107788171901704e+00 +-9.4131649846395937e-02 +3.3506838170392250e-01 +-7.1740636983581463e-01 +-7.5519515066823792e-02 +6.5906735429273111e-01 +-3.7158510457873102e+00 +-8.7100498489535838e-01 +5.5247178799389762e-01 +-2.5022850513889616e+00 +-8.8263120920715987e-01 +5.5367381322264464e-01 +-2.4872370484951003e+00 +-9.6082959691305181e-01 +5.5778855671699468e-01 +-2.4631582737164210e+00 +-9.7230185592722462e-01 +5.5956552570024665e-01 +-2.4634986463175421e+00 +-8.4671247516476211e-01 +5.6929609410904680e-01 +-2.4093453064288846e+00 +-1.1883095522807994e+00 +5.9090123761002844e-01 +-2.4036130305393701e+00 +-8.6543835577657946e-01 +6.0859647952994012e-01 +-2.4774445903915079e+00 +-7.4476920400085822e-01 +6.5835880020930881e-01 +-2.7154271459343331e+00 +-1.0062482432088835e+00 +5.9846196059443790e-01 +-2.2827398469842430e+00 +-7.2883965246073878e-01 +7.5760220586261517e-01 +-2.9527051939409352e+00 +-1.2578037908074000e+00 +6.7127583819984638e-01 +-2.5330621935395841e+00 +-1.2285886092344154e+00 +6.6633672234977370e-01 +-2.4068654439486887e+00 +-9.9002818417982674e-01 +6.9956435370945458e-01 +-2.5558551917630266e+00 +-1.3144772110486456e+00 +7.5587176257229949e-01 +-2.5817359481375490e+00 +-1.2626325777283669e+00 +9.7969846863339261e-01 +-2.6528281434979264e+00 +-3.5143134739111220e-01 +-7.9157766645231442e-03 +-6.5992554088116995e-01 +-8.8973399665332176e-01 +1.0919891276359818e-02 +-2.5346042120730030e+00 +-1.1286823399562882e+00 +3.0987674193455529e-02 +-2.3703754433401234e+00 +-7.7519083683136847e-01 +3.2324474289881139e-02 +-2.3394229880641424e+00 +-1.0961930835322384e+00 +7.3519832124434359e-02 +-1.1730069218569326e+00 +-8.2103467987035172e-01 +3.5303490538316259e-02 +-2.5339632819069648e+00 +-8.9780266717908308e-01 +3.9533154088662120e-02 +-2.3382249264676584e+00 +-2.1442189593398678e-02 +4.2367670046173103e-02 +-2.5881133599259885e+00 +1.6995409290104881e+00 +1.1845238482446917e-02 +-2.6564301877312455e+00 +-1.1394415470107004e-01 +9.0285272323605323e-02 +-6.9159140000411978e-01 +-1.4297753748157177e-01 +8.9942930280030864e-02 +-7.1036005405784608e-01 +-1.1143269987831894e+00 +9.1681769913103894e-02 +-2.3803854879863318e+00 +7.7919758989252227e-02 +8.3628238363561536e-02 +-1.6606534619569653e+00 +2.5363971352201481e-01 +8.1164228103297834e-02 +-2.6481689857751491e+00 +1.2055690487915506e-01 +8.7761305762793340e-02 +-2.5900518527112717e+00 +-1.2969288681841129e-01 +1.0499976065571884e-01 +-7.0154474810753986e-01 +1.3684210721478682e+00 +7.8755913318768953e-02 +-2.3296053312618206e+00 +-6.7899042068662971e-02 +1.1625032345802132e-01 +-6.4245864624149196e-01 +1.4155811545626549e+00 +1.0938295067588590e-01 +-2.2875908364115034e+00 +-4.4272134158029310e-02 +1.2620918106385393e-01 +-2.5905372275015512e+00 +1.0226629798514321e-01 +1.2698478844801550e-01 +-2.4407236893645612e+00 +-6.5524261648115395e-02 +1.2723490418538796e-01 +-6.4302330277361908e-01 +1.4043957827052764e+00 +1.3330689049476538e-01 +-2.2859175360322759e+00 +-7.2896239626977988e-01 +1.6253185321377414e-01 +-2.6643331048677514e+00 +1.4645387127042903e-01 +1.5995427991643474e-01 +-2.6292057054659179e+00 +2.3852834256148658e-01 +1.6185701024328189e-01 +-2.6667028908872328e+00 +2.3852834256148658e-01 +1.6185701024328189e-01 +-2.6667028908872328e+00 +1.3989765886356935e+00 +1.5757219543322915e-01 +-2.2688788703351070e+00 +-6.8968193956169085e-02 +1.4496701341546187e-01 +-6.5022944155007856e-01 +1.5206629804748875e+00 +1.7457153492744457e-01 +-2.2748495025941127e+00 +-1.1763724991360149e-01 +1.5791364357521609e-01 +-6.9001097613201123e-01 +1.3308621494678825e+00 +1.9513338482426443e-01 +-2.4619074503425344e+00 +-1.0428876400103267e-01 +1.7001039882776764e-01 +-6.7885134900949251e-01 +-1.0531506991742994e+00 +2.1854236264512117e-01 +-2.3050134481168794e+00 +-1.0572423809958011e+00 +2.2356138420061361e-01 +-2.5007317936584377e+00 +-6.7974838615072711e-02 +1.6988490207162615e-01 +-6.5091670980219529e-01 +-1.1475144258375196e+00 +2.2349519567099563e-01 +-2.3793772719708701e+00 +-3.8809731435164302e-01 +2.7482598629181604e-01 +-3.9111292862028426e+00 +-3.0690289014433314e-01 +2.7282324777737177e-01 +-3.4508839658816624e+00 +-2.2708744136204040e-01 +2.8847719557049495e-01 +-3.5893185413210595e+00 +-2.9828723524542117e-01 +2.9867624033000068e-01 +-3.7804188912426246e+00 +-8.2750089956887918e-01 +2.7377212166933290e-01 +-2.5645837314779554e+00 +-1.1398959331954228e+00 +2.7666254567702608e-01 +-2.4478325723681444e+00 +-1.1893670080460092e-01 +3.1579509480958018e-01 +-3.2308526247669165e+00 +-7.2351950878708726e-01 +2.9857728389549087e-01 +-2.7527653069637732e+00 +-3.7012459804853309e-01 +3.5631184487910056e-01 +-3.9725051864201197e+00 +-9.8483989322516730e-03 +3.4001514695049811e-01 +-3.4507913765138043e+00 +-4.9719070340191060e-02 +3.2791269781939242e-01 +-3.2571999905571580e+00 +-3.1605138564665214e-01 +3.5328600729637866e-01 +-3.7166255865139126e+00 +3.0839565166149358e-01 +3.0673215765656714e-01 +-2.6108536126996573e+00 +3.0839565166149358e-01 +3.0673215765656714e-01 +-2.6108536126996573e+00 +-2.5278324872384117e-01 +3.6529694190092471e-01 +-3.5132814456886412e+00 +-2.5197088994335537e-01 +3.6616979626167467e-01 +-3.5170936348022552e+00 +2.0515626630729286e-01 +3.4216651559759537e-01 +-2.6974769541322350e+00 +-1.4907473256531245e-01 +2.3465144864440260e-01 +-7.0256349308797528e-01 +-4.6085379304306667e-01 +4.4834555104859269e-01 +-4.2061500573892197e+00 +-6.4263562853213152e-01 +3.7582351245409529e-01 +-2.9886733149285596e+00 +2.0574761764756579e+00 +4.0634020713222235e-01 +-2.9146527603524985e+00 +-5.0194257488198030e-02 +4.0358884198396994e-01 +-3.1494394807944488e+00 +-2.0057953665052311e-01 +4.3082785641551158e-01 +-3.5955027383012572e+00 +-6.4455214435840968e-01 +3.9477440883072878e-01 +-2.9744731773654829e+00 +5.6452070534578525e-01 +4.0274537284261047e-01 +-2.6718553027658047e+00 +3.8767197598924696e-01 +3.9872863605874881e-01 +-2.6194038364641865e+00 +-7.9024796409658526e-01 +3.8396406118455378e-01 +-2.6145656595694287e+00 +2.1222154665212383e+00 +4.4416300046400592e-01 +-2.8598772048340000e+00 +-1.8064171077284963e-01 +4.5334282599212689e-01 +-3.4864002108796401e+00 +-4.1522739574806178e-01 +5.0987841560098257e-01 +-4.0994096140094856e+00 +-3.7916344798780055e-01 +5.2952474491694801e-01 +-4.0446305236469655e+00 +-3.0241778316768869e-01 +5.2739041438768341e-01 +-3.8411856360809464e+00 +-3.2422900407440292e-01 +5.6067835278404832e-01 +-4.1555614986981331e+00 +-3.9705407649618690e-01 +5.5978922931235353e-01 +-4.0755598731465161e+00 +-3.6463684356585468e-01 +5.4820388707805023e-01 +-3.8551610449623235e+00 +1.8512004099919096e-02 +5.2399959771523508e-01 +-3.4547758471427588e+00 +-2.0456643749067055e-01 +5.6821531779378076e-01 +-3.9300894904115906e+00 +-2.8673684166850545e-02 +5.2442781729184773e-01 +-3.3838638810208503e+00 +-1.1060822940642274e+00 +4.1942033966353748e-01 +-2.3912157217243357e+00 +-8.0460583745515901e-01 +4.5268259822026097e-01 +-2.5810915198863160e+00 +-8.0447217346265287e-01 +4.5264382581938978e-01 +-2.5797474200127462e+00 +-1.2005497099145233e+00 +4.2841570843087862e-01 +-2.3166591250689335e+00 +-1.3200149396400790e-01 +5.7969740774381551e-01 +-3.7248714747137233e+00 +-2.6796348308191975e-01 +5.7936114519368087e-01 +-3.7368104182567183e+00 +2.3891840276667645e-01 +5.1782591652509435e-01 +-2.9286642020880804e+00 +2.0277502489262908e-01 +5.2429989684212175e-01 +-2.9029365572442036e+00 +-1.1927064892757745e-01 +3.0960810754137069e-01 +-7.0629387773173702e-01 +-1.0182092483057599e+00 +4.5906973599651829e-01 +-2.2871719235302885e+00 +-9.8397240201508940e-01 +4.7578415761471277e-01 +-2.4542394267075522e+00 +1.0454831649764731e-01 +6.9385149152473213e-01 +-4.2195250825583921e+00 +-2.9603225065395183e-02 +6.5857185370585913e-01 +-3.8359167692133971e+00 +-1.2456029808137741e+00 +4.9305205297564569e-01 +-2.3935713242403280e+00 +-1.3994333631892522e+00 +5.0617875790122824e-01 +-2.6022605790534228e+00 +-2.2256007638320263e-01 +6.5890771176607443e-01 +-3.6940440952748794e+00 +-9.2434211310759767e-02 +6.6957434226305668e-01 +-3.7227862613268679e+00 +-1.3072249187001184e+00 +5.1274328912749612e-01 +-2.3952455604569236e+00 +-7.4385043215129332e-01 +5.6388421098514296e-01 +-2.7534281094357578e+00 +-6.4026167609159457e-01 +6.1798014193298390e-01 +-3.0686163353709461e+00 +-6.4541624118559915e-01 +6.0846478068650600e-01 +-2.9891817376840626e+00 +-9.1354909144293983e-01 +5.8476261038681754e-01 +-2.5383190148224495e+00 +-1.3758845648042324e+00 +5.6291673125230490e-01 +-2.4046708279728515e+00 +-7.7628414046925076e-01 +6.3363117362289356e-01 +-2.6298402721219030e+00 +-8.4456924343068618e-01 +6.0468953157645022e-01 +-2.4987412666172806e+00 +-8.5470130908959996e-01 +6.0419700875157212e-01 +-2.4823222586143485e+00 +-1.0089795609045635e+00 +6.0507517476970218e-01 +-2.4160603252887598e+00 +-7.3036777015177423e-01 +6.5825351177381641e-01 +-2.7297929581685643e+00 +-9.0949976500843988e-01 +6.0943308080302827e-01 +-2.4329712699009303e+00 +-9.2003144581667762e-01 +6.0503281714494106e-01 +-2.4320575853553095e+00 +-9.5278933588307335e-01 +6.1270836637010073e-01 +-2.4109868718649388e+00 +-9.5947020167006936e-01 +6.0314817606179594e-01 +-2.3778694002845073e+00 +-1.0486511235644749e+00 +6.1890839525240615e-01 +-2.4049065082679668e+00 +-1.0218334990852780e+00 +6.2660925306653181e-01 +-2.4352953490304556e+00 +-1.1454604940135313e+00 +6.1340474036013981e-01 +-2.3633493458026691e+00 +-1.1896056272756832e+00 +6.3747719743329068e-01 +-2.5600295966736928e+00 +-1.2229116162460101e+00 +6.3764683031917924e-01 +-2.5621553914187323e+00 +-1.2741790333859284e+00 +6.4027007537002156e-01 +-2.5828345342649950e+00 +-8.8730291766536062e-01 +6.9232761146408228e-01 +-2.6730887452146694e+00 +-7.9111181455238511e-01 +7.1116779816184938e-01 +-2.5681946485873084e+00 +-1.1454098039886815e+00 +7.0731378598780303e-01 +-2.3657043044370103e+00 +-9.9624297610588541e-01 +7.2545566370310788e-01 +-2.3970108666300911e+00 +-1.1099620831295758e+00 +7.1555857675953605e-01 +-2.3825331016798228e+00 +-1.2999917142762145e+00 +7.8186438024129490e-01 +-2.6167942972910665e+00 +-9.3417304808341062e-01 +9.0564331442733326e-01 +-3.0408302586550477e+00 +-1.0906228749401616e+00 +8.0259878690272712e-01 +-2.5234228631808828e+00 +-1.2688862320979291e+00 +9.2717525847508364e-01 +-2.4918079500215686e+00 +-8.0104033737982894e-01 +6.6521052327713891e-03 +-2.6275310786458519e+00 +-8.2991535632771363e-01 +1.9943756747182465e-02 +-2.3790283498181686e+00 +1.4393252529430303e+00 +-1.6225917655633186e-02 +-2.2381190895638015e+00 +1.6255766815909587e+00 +-4.7163298458794195e-03 +-2.1987385476328845e+00 +-7.9240319713779572e-01 +3.7272830091411295e-02 +-2.3354920963634473e+00 +-1.0363509486840150e+00 +6.1949035740980124e-02 +-1.5892913078553303e+00 +-7.9789279221395537e-01 +5.1087422894707163e-02 +-2.5494055152832944e+00 +-9.3067499539361387e-01 +5.8243484203845793e-02 +-2.3195504261703701e+00 +-9.0862838951142899e-01 +7.3834424287938460e-02 +-2.5010208217508261e+00 +3.4733610591097173e+00 +-5.9915941205799475e-02 +-6.5896145499953569e+00 +-7.8167441168636553e-01 +7.4971557179409190e-02 +-2.5867054623448555e+00 +-1.0789673504429800e+00 +8.0297255670330581e-02 +-2.3940063539610916e+00 +-8.1527846885484867e-01 +7.5604494657829799e-02 +-2.4859678659386604e+00 +-9.9859124194408011e-01 +8.6282161861982148e-02 +-2.3059638600619516e+00 +-8.1553206242050902e-01 +8.2784807977726416e-02 +-2.5490078439602821e+00 +-9.0228119530806095e-01 +9.1099074556471038e-02 +-2.4686058903669901e+00 +-6.6372702955941021e-01 +1.1560691773940757e-01 +2.7138282417163090e-01 +-1.1284523342146551e+00 +1.0818838881097835e-01 +-2.3666445786708881e+00 +-1.1425605731431738e+00 +1.0973554121687804e-01 +-2.4011025041652898e+00 +-1.0082287461918804e+00 +1.1445930661254013e-01 +-2.4734510022742673e+00 +-1.1280328536691817e+00 +1.1833920255773696e-01 +-2.3763760778873553e+00 +-1.3137895292050356e-01 +1.1242167077590111e-01 +-6.9529928648198847e-01 +-1.3137895292050356e-01 +1.1242167077590111e-01 +-6.9529928648198847e-01 +-9.0192510866355535e-01 +1.1850259207236037e-01 +-2.4871640066907226e+00 +-1.2545992613005047e-01 +1.2138159947506923e-01 +-6.9483122714508805e-01 +-1.1282213570736277e+00 +1.3710548819800605e-01 +-2.3777006488773718e+00 +-1.0616489323177168e-01 +1.2554061765000646e-01 +-6.7748221676279574e-01 +-1.0095821783850836e-01 +1.2768646552718937e-01 +-6.8307271936368275e-01 +-1.0286115858673808e-01 +1.3167211071426466e-01 +-6.7905696474427224e-01 +-8.3789587305603819e-01 +1.6089659931629374e-01 +-2.4205530080847675e+00 +-1.1426957814659779e+00 +1.5137374873039938e-01 +-2.3903025119690184e+00 +-1.1271685296516720e+00 +1.7325816921278722e-01 +-2.3622756238323812e+00 +-8.4227610313919177e-01 +1.9176865472943408e-01 +-2.4008263355413373e+00 +8.2900458265905930e-01 +1.9278142971753362e-01 +-2.9682246210465859e+00 +6.1242635630668196e-01 +1.9047313986929729e-01 +-2.7682203850803000e+00 +-9.0525977680617309e-01 +1.9244404839122448e-01 +-2.3235825482428933e+00 +2.0349384126343595e+00 +1.8791470009159550e-01 +-2.4268950253609791e+00 +2.0349384126343595e+00 +1.8791470009159550e-01 +-2.4268950253609791e+00 +-7.2650464067968856e-01 +2.0790122912578074e-01 +-2.7182840191489777e+00 +1.5580602365193257e+00 +1.9413321325621422e-01 +-2.2683673969880056e+00 +8.1096443393027962e-01 +2.1220334071871796e-01 +-2.9302554892660408e+00 +-9.0171434048388011e-01 +2.0584776062808174e-01 +-2.5176940900805720e+00 +-8.3837007457737966e-01 +2.2985015466091799e-01 +-2.9452045389864949e+00 +-9.4860605611932614e-01 +2.0253951026954220e-01 +-2.3174747929919985e+00 +-8.7689839536524872e-01 +2.1304162475430605e-01 +-2.4484602425635438e+00 +-1.0110190981164486e+00 +2.1457252238843522e-01 +-2.4151587176758929e+00 +-1.0506714090862372e+00 +2.1181972660125453e-01 +-2.3072947996118600e+00 +-1.0521648925651952e+00 +2.1278303053254127e-01 +-2.3822798508922411e+00 +-9.3978340600052013e-01 +2.1225446486335547e-01 +-2.3139301631310070e+00 +-1.1486684367935249e+00 +2.1764325766008946e-01 +-2.3787898746863996e+00 +-1.0169119731796710e+00 +2.1972009587496114e-01 +-2.4764705192085334e+00 +-3.9207607994035559e-01 +2.7735678729945090e-01 +-4.0113338835585033e+00 +1.5885337943861664e+00 +2.2706483313204018e-01 +-2.2126012113538875e+00 +1.5878015402231525e+00 +2.2664261302654490e-01 +-2.2119543058206776e+00 +-4.3787521453534051e-01 +2.9129961884547712e-01 +-4.1253370019945210e+00 +1.5527828892582682e+00 +2.3348586379144576e-01 +-2.2182811435778000e+00 +-4.0969177705854931e-01 +2.9274201668291044e-01 +-4.0559031990186725e+00 +-1.6038189284994395e-01 +2.7314595705509914e-01 +-3.4171404534367626e+00 +-1.1267435002008086e+00 +2.4209736646652386e-01 +-2.3755321722329645e+00 +-1.1369083222032246e+00 +2.4383082290931829e-01 +-2.3789612295745943e+00 +1.5536504584331687e+00 +2.4426089106780940e-01 +-2.2589495340319008e+00 +-3.2996540442135081e-01 +3.0024650371670941e-01 +-3.8673589552214400e+00 +4.6269639597714468e-01 +2.6247018117433069e-01 +-2.6344092640910999e+00 +-3.3645292382517185e-02 +2.8771931968984310e-01 +-3.2223321227100521e+00 +1.6543422496639042e+00 +2.5598192916637263e-01 +-2.1643693869888492e+00 +-7.2741875994081717e-01 +2.7470823119942256e-01 +-2.8722453226226579e+00 +-7.9635458809389759e-01 +2.7094842970152011e-01 +-2.5680323592497154e+00 +-8.1415424991786489e-01 +2.7505862488614025e-01 +-2.5318731934495493e+00 +2.0057055516056121e+00 +2.9240290832779864e-01 +-2.4503149921665934e+00 +-3.1249385306791783e-01 +3.4496774373331884e-01 +-3.8013782436246695e+00 +-8.7463581478252583e-01 +2.7768218212881107e-01 +-2.3408703521080181e+00 +-2.8910246645589266e-01 +3.5042330398411337e-01 +-3.8254099409140632e+00 +-6.9729885063742036e-01 +1.5785222296681184e-01 +4.6514636524544123e-01 +1.6240058304113167e+00 +3.0273483073142388e-01 +-2.2623018367600367e+00 +-1.1463942652376806e+00 +2.9394808005899459e-01 +-2.3755666864974216e+00 +-8.5393180848259809e-01 +3.0769519662645678e-01 +-2.4853512607328803e+00 +-3.5486582936139194e-01 +3.7980411708203810e-01 +-3.8233551897870077e+00 +-9.4691251318391723e-01 +2.9708004784255582e-01 +-2.3563325804594490e+00 +-2.8505734575400155e-01 +3.8949940891753099e-01 +-3.7803534220352004e+00 +-9.3557530719272175e-01 +3.1473957731208269e-01 +-2.4371679829482464e+00 +-9.5268025680447233e-01 +3.0980383278528678e-01 +-2.3151443809547207e+00 +-2.6960323156977201e-01 +3.9604454791712074e-01 +-3.6917563053252511e+00 +-4.6627616994990972e-01 +4.3670931503466665e-01 +-4.2427551095337064e+00 +-1.3829856058466414e-01 +2.3332770581245429e-01 +-6.9614517943556375e-01 +-7.6856360252982270e-01 +3.4723212133828774e-01 +-2.6440683462428538e+00 +-4.2416495523803871e-01 +4.3874346335381276e-01 +-4.1327139607389620e+00 +-4.1537644968939502e-01 +4.4107578118545432e-01 +-4.1276746279487622e+00 +-4.1939168213327704e-01 +4.3919875860299351e-01 +-4.0733036953796073e+00 +-1.5234272137488755e-01 +2.3697736249655466e-01 +-7.0489648720988052e-01 +-1.5237396716085255e-01 +2.4748496030106837e-01 +-7.0182255823504791e-01 +-7.2994072248708686e-01 +3.6604917963227102e-01 +-2.6159647553929410e+00 +-5.5811478423523804e-02 +4.0880917522482485e-01 +-3.1352818051891465e+00 +5.0191224211454122e-01 +3.9546474115693669e-01 +-2.6774431611198666e+00 +1.9951806955286795e+00 +4.3213487987477733e-01 +-2.8685351689019760e+00 +-1.5050542920625753e-01 +4.4309449079609081e-01 +-3.4795671086631095e+00 +-3.9311068173511010e-01 +4.8456118755553451e-01 +-3.8668373644979912e+00 +-3.9311068173511010e-01 +4.8456118755553451e-01 +-3.8668373644979912e+00 +2.4009827568997841e-01 +4.4563388561389211e-01 +-3.1183002529127992e+00 +-4.5135832991155507e-03 +4.3585351994851612e-01 +-2.8455243911905845e+00 +-1.1937163159735229e+00 +3.8607705440344525e-01 +-2.3894716078845226e+00 +1.5245778343777272e-01 +4.3333241072717454e-01 +-2.8217693334860932e+00 +-4.3934671800040731e-01 +5.4157236772328077e-01 +-4.2058923036650846e+00 +-4.3040000627924935e-01 +5.4559407275241190e-01 +-4.2203325610081741e+00 +-8.9359209843580922e-01 +4.1320099046421804e-01 +-2.5427510514825200e+00 +-3.9796673717838854e-01 +5.4609295973311001e-01 +-4.0904875985263383e+00 +2.3762132569347907e-02 +4.5793355576740180e-01 +-3.0017424349749393e+00 +1.1257950039681261e-01 +4.9712885458561762e-01 +-3.3103137657827864e+00 +2.2283679989675428e-01 +4.5216774385494213e-01 +-2.7211372556646816e+00 +-1.3288438371198306e+00 +4.0417336745795379e-01 +-2.3707054634449540e+00 +-9.4137226039610145e-01 +4.1349925722063363e-01 +-2.4438182559839929e+00 +-1.2928539969557793e+00 +4.0831930484792894e-01 +-2.4000228805403898e+00 +-7.3677875401911364e-01 +4.4718399249018947e-01 +-2.6935796615211873e+00 +3.3304193439905144e-01 +4.5435082728948872e-01 +-2.6116778137008274e+00 +4.8682628042383526e-02 +5.3459785653258263e-01 +-3.5520900500465422e+00 +1.2105219191609275e-01 +4.8467174718725703e-01 +-2.8941625606003889e+00 +-3.1155246014600846e-01 +5.6271827005479735e-01 +-3.7737750778287618e+00 +-1.1363780143403750e+00 +4.3917693383238582e-01 +-2.4148658434889674e+00 +-7.9283703044197229e-01 +4.6918780358543172e-01 +-2.6950000814267869e+00 +-8.2019446543595009e-01 +4.7364761722340054e-01 +-2.5710187346055928e+00 +-1.1234134708837644e+00 +4.5015988974626320e-01 +-2.3896817493193270e+00 +-8.9597901151789772e-01 +4.6758661542013163e-01 +-2.4990714688510867e+00 +-1.6843648404103594e-02 +3.0979336115494921e-01 +-6.9713678782247923e-01 +-9.8291022772252956e-01 +4.6302031471112487e-01 +-2.4167451227152439e+00 +-1.3398885283396411e+00 +4.7601511759573406e-01 +-2.5787787088374010e+00 +-9.0369593937174442e-01 +4.6908985547266802e-01 +-2.4276350897498666e+00 +-6.9790438596869092e-02 +3.1930036632036907e-01 +-6.7414122058209691e-01 +-9.3829466609104595e-01 +4.8269031957592251e-01 +-2.4719848594966822e+00 +1.1519171313102082e-01 +6.9289252970691906e-01 +-4.2205871066507896e+00 +-3.0967784135322862e-01 +6.5706829278630463e-01 +-3.9484564991304043e+00 +-8.7262281279944753e-01 +4.9439419192181350e-01 +-2.4519644100047637e+00 +-8.8378171351915447e-01 +5.2087486349770684e-01 +-2.6079797206212714e+00 +-8.8533261244828232e-01 +5.0541984199188938e-01 +-2.4950196055569891e+00 +-1.3373535636416145e+00 +4.9475994267643492e-01 +-2.4069562405740048e+00 +-1.6414709842348996e-01 +6.6353401000062584e-01 +-3.7679987160945463e+00 +-1.2658791711256152e+00 +5.1205168176970106e-01 +-2.3924231373670688e+00 +-6.4212663848879847e-01 +6.2569361970095472e-01 +-3.0697317167039579e+00 +-1.3477680960272980e+00 +5.3735419240319715e-01 +-2.3887435906934193e+00 +-1.4111892727440309e+00 +5.4365652864540348e-01 +-2.3821986337841605e+00 +-8.0063048097514766e-01 +5.9771738033870059e-01 +-2.5793872434377949e+00 +-1.2956184519707461e+00 +5.7587398096164577e-01 +-2.4923586795036066e+00 +-6.7691251154346233e-01 +6.5546816780169737e-01 +-3.0024208357411064e+00 +-8.1731052269693794e-01 +5.9097128077759076e-01 +-2.4916622486891233e+00 +-8.4046954967673526e-01 +5.9180479781131590e-01 +-2.4851277809056129e+00 +-8.5037754693245782e-01 +5.9764042699648867e-01 +-2.4972381836133053e+00 +-8.5809017544561594e-01 +5.9366432459875373e-01 +-2.4711115553056224e+00 +-1.1582717424429190e+00 +5.9493524496126360e-01 +-2.4550370466480369e+00 +-9.0868075788288927e-01 +6.1215045500026821e-01 +-2.4983507798862337e+00 +-8.4219401301107732e-01 +6.3051308669757256e-01 +-2.5286522457718252e+00 +-8.5098501626880585e-01 +6.3490430565373557e-01 +-2.5941647932696061e+00 +-1.2313983972781541e+00 +6.2853730905648431e-01 +-2.5649331794127401e+00 +-9.6170727045722237e-01 +6.1203765906092356e-01 +-2.3437303411170070e+00 +-1.1643638650220862e+00 +6.2148236776584520e-01 +-2.3881184924809484e+00 +-1.3883937251239742e+00 +6.1337087849020799e-01 +-2.4303399645212247e+00 +-7.8906591530713199e-01 +6.8845654135085199e-01 +-2.7721157053251084e+00 +-8.9566252726559892e-01 +6.2605551049733543e-01 +-2.4379323191703572e+00 +-1.3569761355987027e+00 +6.2372681671527830e-01 +-2.4093971914701133e+00 +-1.3819286763859762e+00 +6.2382515142249240e-01 +-2.4112858567926998e+00 +-1.0230181946194588e+00 +6.4572740779604998e-01 +-2.5380545910362620e+00 +-9.7315972304885212e-01 +6.3006909948486478e-01 +-2.3197900255784267e+00 +-8.0333593462232555e-01 +7.1907759986365627e-01 +-2.6954626939460753e+00 +-1.1251881756376130e+00 +6.6314814624292284e-01 +-2.3320186178976123e+00 +-1.3132780899079353e+00 +7.0200610413601905e-01 +-2.6078208806895256e+00 +-1.0653532240745756e+00 +6.9891754871476286e-01 +-2.4056866775756598e+00 +-1.0653532240745756e+00 +6.9891754871476286e-01 +-2.4056866775756598e+00 +-8.8331951312622525e-01 +7.3215078660729116e-01 +-2.5038993112284964e+00 +-9.8192159132534762e-01 +7.3298991348441311e-01 +-2.5761384805167293e+00 +-9.8863569456741873e-01 +7.3316034216037729e-01 +-2.5743772343167137e+00 +-9.5061236052202636e-01 +7.3210644826563831e-01 +-2.4863645572730104e+00 +-1.0024234304645512e+00 +6.9803064999960573e-01 +-2.2895819045044630e+00 +-1.1242783900444600e+00 +7.4196509728737536e-01 +-2.4728011158548404e+00 +-1.1189633984922920e+00 +7.2589474778165819e-01 +-2.4031635176658281e+00 +-1.2934068150709903e+00 +7.6923470202480670e-01 +-2.6099446190195197e+00 +-1.1774897284685588e+00 +7.9281765061070930e-01 +-2.5947685503166147e+00 +-1.3614323340426098e+00 +7.8976379109471784e-01 +-2.4502702597688226e+00 +-1.1409251735241119e+00 +9.6588591482841535e-01 +-2.9325992562202989e+00 +-5.9302611063111993e-02 +1.0130548412340561e-02 +-2.4592322481347906e+00 +1.4738454994406689e+00 +-9.6353413600324140e-03 +-2.2371291757096086e+00 +-4.6685637581605273e-02 +6.3732951102129676e-02 +-6.0267436421390308e-01 +-1.0985206782640067e+00 +3.5564449827456768e-02 +-2.3898102709841376e+00 +1.6356227749235956e+00 +-6.1357520930920024e-03 +-2.2730222384648222e+00 +-1.1695105674493801e-01 +7.4767547634472062e-02 +-6.9186533271077710e-01 +-1.0026003213339165e+00 +6.9233683373042754e-02 +-2.2959153694958467e+00 +-1.0168643986364907e+00 +6.2296059671940004e-02 +-2.4614774550121732e+00 +9.9873158312697463e-01 +3.7708632533283340e-02 +-3.1783184361455663e+00 +-8.0999345912799470e-01 +7.8069728384903544e-02 +-2.4337638090709519e+00 +-8.5061720076231206e-01 +8.4860860057908480e-02 +-2.5025057961162953e+00 +-9.2841852875998310e-01 +8.4288579328961000e-02 +-2.3676667476434257e+00 +-9.1131151104106800e-01 +8.8516712644355358e-02 +-2.3368170441627609e+00 +-1.0268445125990291e+00 +9.5076684581779619e-02 +-2.3161049695877725e+00 +1.4350285902051692e+00 +8.7744073531352884e-02 +-2.3048548876642614e+00 +-8.8913557737752558e-01 +1.1647211563463392e-01 +-2.4914233673836339e+00 +-7.8960956341462452e-01 +1.4385470094585354e-01 +-2.6058864049447039e+00 +1.5429334690300851e+00 +1.2553303649916314e-01 +-2.2445108667813138e+00 +1.5429334690300851e+00 +1.2553303649916314e-01 +-2.2445108667813138e+00 +-7.7020183219400629e-01 +1.4771138709965423e-01 +-2.5870637511805250e+00 +-8.0826697627847444e-01 +1.5633860385543571e-01 +-2.5511559982064576e+00 +-1.0029049159817338e+00 +1.5741280459718060e-01 +-2.4339200660910034e+00 +-8.9198513764881182e-01 +1.5895342045977104e-01 +-2.4909994510561990e+00 +-7.4871834447733043e-01 +1.6013518500501289e-01 +-2.6801715092850991e+00 +2.0065744050544398e+00 +1.4161433786470881e-01 +-2.3546887078919836e+00 +-8.1647204094400183e-01 +1.6559904385701346e-01 +-2.5761128402598863e+00 +-9.5533377585968349e-01 +1.6655423343346312e-01 +-2.4547136741330484e+00 +-8.7305459385617945e-01 +1.6764773496514873e-01 +-2.5019771004134799e+00 +-1.0743744523834176e+00 +1.6974563350991556e-01 +-2.3965065845897380e+00 +-7.9504873591863978e-01 +1.7872949048074543e-01 +-2.5816671851323303e+00 +-7.5835621529187436e-01 +1.7710324639702474e-01 +-2.4327075342744662e+00 +-7.9881111562583229e-01 +1.8419903030244902e-01 +-2.5186956267900471e+00 +-9.3902485155051252e-01 +1.8526197876894179e-01 +-2.4524562262167664e+00 +-8.8855137593878064e-01 +1.9189342191436459e-01 +-2.4774785607513690e+00 +-1.1504001715997882e+00 +1.9172796041162282e-01 +-2.4099265654964728e+00 +-1.1449081811367672e+00 +1.8759300799704415e-01 +-2.3267582728530187e+00 +2.0383805249323546e+00 +1.8072964229543287e-01 +-2.4119031732680360e+00 +-8.9895815809297919e-01 +1.8868802257450112e-01 +-2.4326890003598063e+00 +-9.1424242985519766e-01 +1.9114190236611733e-01 +-2.3752220003485802e+00 +-1.0159004871891153e+00 +1.9301914533051448e-01 +-2.3820273208358702e+00 +-1.1034307200061386e+00 +2.1765245673139089e-01 +-3.5741789996887596e+00 +-7.5962107014921465e-01 +1.9812745282539693e-01 +-2.5978261469935537e+00 +-8.1525120032908571e-01 +2.0058504497431853e-01 +-2.5734080108046840e+00 +-1.1510424312161494e+00 +2.0052548934003608e-01 +-2.4264212032968495e+00 +-1.0285984477807510e+00 +1.9940346835455061e-01 +-2.3997501330178674e+00 +-1.1762232587109318e-01 +1.6156595992688350e-01 +-7.0178921392553140e-01 +-1.1492518524849740e+00 +2.0393501715661094e-01 +-2.4747136990171144e+00 +-7.7684954328764391e-02 +1.6264645050839169e-01 +-6.7602478861240611e-01 +-8.4312085010957538e-01 +2.0275526610417133e-01 +-2.4185358005971986e+00 +-8.7690708648041349e-01 +2.1183320632188046e-01 +-2.4756558521538303e+00 +-8.7690708648041349e-01 +2.1183320632188046e-01 +-2.4756558521538303e+00 +-1.2502582853672515e+00 +2.7033014608584427e-01 +-4.6707179601901352e+00 +-9.8770919064630913e-01 +2.0992929707634311e-01 +-2.3086041509744142e+00 +-1.0037653699633649e+00 +2.1252494192956592e-01 +-2.3284969433003671e+00 +-9.3178265959893491e-01 +2.2160303480599094e-01 +-2.5260149224757926e+00 +1.5683996990656679e+00 +2.3501827531351710e-01 +-2.2768539041465652e+00 +1.5683996990656679e+00 +2.3501827531351710e-01 +-2.2768539041465652e+00 +-7.3089648812384500e-01 +2.5030827282073426e-01 +-2.6824712504368824e+00 +-7.4149599284904666e-01 +2.4419675163182378e-01 +-2.5871264733870794e+00 +-8.0344390584049052e-01 +2.5540260970440504e-01 +-2.6207887270247392e+00 +1.5836941675261174e+00 +2.5041495779476791e-01 +-2.2031375909254947e+00 +-7.8644815618480735e-01 +2.6115850976958377e-01 +-2.5610589405320581e+00 +-8.0976652091022461e-01 +2.6400336963195475e-01 +-2.5379817161073550e+00 +1.4569838505866095e+00 +2.6270665188226128e-01 +-2.2065762622209029e+00 +-4.3305614386784663e-01 +3.3492071201420232e-01 +-4.1084547067169899e+00 +-1.1233585995206272e+00 +2.7145474198836878e-01 +-2.4307889368615343e+00 +-1.1220662176850806e+00 +2.6822763757234153e-01 +-2.3683141223874125e+00 +1.3522720387377174e+00 +2.7888078497975521e-01 +-2.3377609017289154e+00 +1.3656431780563960e+00 +2.7911469931134431e-01 +-2.3198250720137810e+00 +1.4666937265497411e+00 +2.9100890553669911e-01 +-2.2201446386909818e+00 +1.6953855200084995e+00 +3.0073924361244742e-01 +-2.3165664305336979e+00 +1.7079682969790038e+00 +3.3917052639016104e-01 +-3.1020499885258910e+00 +-4.3100920491619948e-01 +3.8437999667469336e-01 +-4.1522741617508450e+00 +-8.9342337509492031e-01 +3.0009784348053486e-01 +-2.4205932775100760e+00 +-6.4360094336575846e-01 +3.3739191629016813e-01 +-3.0144695482009887e+00 +-8.0897450381598923e-01 +3.1304895045144365e-01 +-2.5113076525781133e+00 +-1.0035736522685357e+00 +3.0156054753183203e-01 +-2.3106042811584300e+00 +-4.5115724322752598e-01 +4.2482430479279060e-01 +-4.2353050868392321e+00 +-1.4506694158187322e-01 +2.2862095625461085e-01 +-7.1192669133062692e-01 +-8.1071425805235117e-02 +3.8245782952801666e-01 +-3.3108430215025755e+00 +-1.1564512047891760e+00 +3.2848123188662592e-01 +-2.3826136529191206e+00 +2.0507557291142660e+00 +4.1887082658173308e-01 +-2.9172947344621263e+00 +-1.6505326804807680e-01 +4.2799255150040533e-01 +-3.4369431320240871e+00 +-4.1637316115208750e-01 +4.7894044092386473e-01 +-4.1084650904286057e+00 +-4.1734270501293796e-01 +4.7987100150896678e-01 +-4.0851191067945312e+00 +-4.4449927926698951e-01 +4.9294774074487763e-01 +-4.2435239327468848e+00 +-8.3086562055602575e-01 +3.7138700273809333e-01 +-2.4394753441400217e+00 +2.1206730451225804e+00 +4.3471094878412103e-01 +-2.8600108504041306e+00 +-4.2134225564125710e-01 +4.9348514423857637e-01 +-4.1695073109394540e+00 +-4.2134225564125710e-01 +4.9348514423857637e-01 +-4.1695073109394540e+00 +-7.6145992189762257e-01 +4.0072854676638547e-01 +-2.6515300571249889e+00 +-7.2133243150595572e-01 +4.1518475941298771e-01 +-2.7969999729758492e+00 +-7.2734048890307712e-01 +4.0740356866551847e-01 +-2.6979113190337256e+00 +-6.3243289553845972e-01 +4.3481751770392929e-01 +-3.0229020567632308e+00 +-6.3243289553845972e-01 +4.3481751770392929e-01 +-3.0229020567632308e+00 +-1.6270347182945250e-01 +4.7271860038293428e-01 +-3.4111576191790269e+00 +2.0831843206358616e+00 +4.7063425019486116e-01 +-2.8241834077926540e+00 +-4.6640647823782931e-02 +4.9321448058381023e-01 +-3.5140968323358712e+00 +-8.0385777373680922e-01 +4.1435783115985914e-01 +-2.5796046893903775e+00 +-7.4804323651770588e-01 +4.2687586831651675e-01 +-2.7217862713352345e+00 +1.0750589718525960e-01 +4.5039949601408552e-01 +-2.8931444139173563e+00 +1.3149902821439813e-01 +4.4255637232767947e-01 +-2.7708003815482494e+00 +-9.2408869754498663e-02 +4.8607515030801834e-01 +-3.2976792221312792e+00 +-2.9956726927060615e-02 +5.4058968511048378e-01 +-3.8033675177781068e+00 +-1.0663603459897242e+00 +4.0724601092097001e-01 +-2.3786099981653881e+00 +-9.3626946166834768e-01 +4.0168273573438640e-01 +-2.3117024931669583e+00 +-9.8402152520317721e-01 +4.1716344903298985e-01 +-2.4059734510103179e+00 +-9.5077827862080599e-01 +4.1764123988243912e-01 +-2.3075274925751850e+00 +-1.1571833761218806e+00 +4.3639773187572656e-01 +-2.4987130927066259e+00 +4.0356228938158149e-02 +5.0072034528258358e-01 +-2.9267060783380439e+00 +-1.1761458841753905e+00 +4.0870479435407853e-01 +-2.2014878241637676e+00 +-3.6508515658162204e-02 +5.5424157545124964e-01 +-3.5635719546886357e+00 +4.8246680112178725e-02 +5.1851412048318524e-01 +-2.9248193534952986e+00 +-1.0748880920920567e-01 +3.1442185910019643e-01 +-7.1801154988224947e-01 +-8.3702274303448276e-01 +4.8157890339573972e-01 +-2.5444418352786005e+00 +-1.1384085682408004e-01 +3.1872786901516503e-01 +-7.1828263481753118e-01 +-7.8423868348972359e-01 +4.9838988693114772e-01 +-2.5986137819885422e+00 +-2.9993877056263823e-01 +6.2578095106374765e-01 +-3.7044832038448354e+00 +-1.2674482664030626e+00 +4.7789963468476421e-01 +-2.3375807879577337e+00 +-1.2117794344156982e+00 +4.8879372265069965e-01 +-2.3864344114124685e+00 +-7.3183342282595198e-01 +5.2976136127579487e-01 +-2.6727025677758274e+00 +-4.2001920684027270e-02 +6.6711982946654336e-01 +-3.8418586113821567e+00 +-4.2769273596418786e-02 +6.6374850083234249e-01 +-3.7984277692453214e+00 +-1.3528207203454192e+00 +4.8607297150565915e-01 +-2.3340194168061874e+00 +-1.0581521233236825e-01 +6.7032580160081767e-01 +-3.8098572463185287e+00 +-1.1129485417399327e+00 +5.0480973528802275e-01 +-2.3868517305656494e+00 +-1.1551141529876934e+00 +5.1060953333577752e-01 +-2.3825968246778566e+00 +-1.1940428491662523e+00 +5.2407370057817770e-01 +-2.5223969548724332e+00 +1.2678013423524476e-01 +5.9710491608982019e-01 +-2.9484610650623613e+00 +-1.0759665596373793e+00 +5.1712226150829432e-01 +-2.3890366124013833e+00 +-1.1155587802825844e+00 +5.1352004095784443e-01 +-2.3922903162581757e+00 +-1.1589754213533980e+00 +5.1492586741437119e-01 +-2.3796541782029479e+00 +-1.1774266243446008e+00 +5.4084866724670599e-01 +-2.2991018605704294e+00 +-1.2383424550135129e+00 +5.6946478342189510e-01 +-2.5290089338380994e+00 +-1.2461772818002803e+00 +5.4284226511321620e-01 +-2.3117149302220708e+00 +-1.3920155564651198e+00 +5.7560709029142343e-01 +-2.6069776051344253e+00 +-7.7192687701329610e-01 +5.8467905962615307e-01 +-2.5425300041217818e+00 +-8.0964027974873065e-01 +5.6542205413136415e-01 +-2.4582355407621970e+00 +-7.6258536891055817e-01 +6.2712722216029237e-01 +-2.7891782104638576e+00 +-7.6893864837433046e-01 +6.0779101770519550e-01 +-2.6446079788794918e+00 +-8.8640255892955744e-01 +6.1207512164527289e-01 +-2.5674938037201334e+00 +-8.7429795840523561e-01 +6.1239914709582588e-01 +-2.5062015083490352e+00 +-8.9426070333615837e-01 +5.9240247991532458e-01 +-2.4157229997156597e+00 +-1.2182230127824600e+00 +5.9070567432632903e-01 +-2.3785373082785006e+00 +-1.0005350499796588e+00 +5.9680851694821879e-01 +-2.3733832142797224e+00 +-1.0016830071205440e+00 +6.3783746156460608e-01 +-2.5797849661922898e+00 +-6.9782345305452409e-01 +6.8218044679249490e-01 +-2.7131783109460836e+00 +-9.3136644179818773e-01 +6.5017806211889750e-01 +-2.5079116413754252e+00 +-9.5347722758324371e-01 +6.4905074032357546e-01 +-2.4915203407707467e+00 +-9.9770708743800662e-01 +6.3528664188889472e-01 +-2.4018358956999166e+00 +-1.0029671931226707e+00 +6.5110315622899806e-01 +-2.4752073759605935e+00 +-1.1775639330113892e+00 +6.3650333699206718e-01 +-2.3876772640949961e+00 +-1.0633234171704493e+00 +6.2702050101026763e-01 +-2.2878722898503043e+00 +-8.6909420942844839e-01 +6.6087260109927048e-01 +-2.4925912984065146e+00 +-9.9843880386608530e-01 +6.6457757540418960e-01 +-2.4243447956449340e+00 +-1.3741813208358469e+00 +6.4036221482886113e-01 +-2.3417163837574830e+00 +-1.1572277248595937e+00 +6.6732738129112934e-01 +-2.3895722564968533e+00 +-1.2309961124373736e+00 +8.2469272897300216e-01 +-3.2551466919799537e+00 +-8.7430136115964496e-01 +7.2343753309526238e-01 +-2.6126991944144420e+00 +-9.9698784854969380e-01 +7.0327222678040335e-01 +-2.4108121381113738e+00 +-1.3606144060293177e+00 +6.9026120627645526e-01 +-2.3644020003314212e+00 +-1.3441971840518054e+00 +9.2750686222430578e-01 +-3.5496909472643781e+00 +-1.2402177586670318e+00 +7.7216331439572183e-01 +-2.5873887442906431e+00 +-9.9721661074394163e-01 +7.3226377105084506e-01 +-2.2693822772301910e+00 +-1.0165074020517915e+00 +7.7661161211932928e-01 +-2.4805121142270359e+00 +-1.2010496276893898e+00 +7.6747465834747941e-01 +-2.3005470050341095e+00 +-1.2713174339026427e+00 +8.9902043792042008e-01 +-2.4837568875317655e+00 +-4.2318652414885355e-01 +7.6033661823073015e-03 +-6.4912887261342744e-01 +1.9876317361695479e+00 +-9.8208527717471697e-02 +-2.3643311247553895e+00 +3.9975496880854905e-01 +-3.6304658529517912e-02 +-2.5467753821670618e+00 +-1.1009739073238221e+00 +5.0608348749962340e-02 +-1.0655934961189539e+00 +-1.1139721778422245e+00 +5.1230124792716936e-02 +-1.1508814133182834e+00 +3.6379152483294003e-01 +-2.2557877846197175e-02 +-2.5337211188928528e+00 +-1.1318638582309661e+00 +3.6176372717209138e-02 +-2.3683502243089354e+00 +-1.1318638582309661e+00 +3.6176372717209138e-02 +-2.3683502243089354e+00 +1.6726604223503692e+00 +1.3084433335286381e-02 +-2.3119711332817072e+00 +1.5927697855172587e+00 +1.6269504641417926e-02 +-2.2133155974154306e+00 +-9.0926993713056470e-01 +6.1650302514759225e-02 +-2.3295691911774039e+00 +-8.2077658805807496e-01 +6.3145205460009346e-02 +-2.5127380128115813e+00 +-8.1725236955512792e-01 +5.9021736145459615e-02 +-2.5919612598484205e+00 +-1.0454031653423823e+00 +6.9499215842167644e-02 +-2.3017747286784278e+00 +1.4869166983158102e+00 +4.0982016050794545e-02 +-2.2900736550035483e+00 +-8.0235113325066831e-01 +8.2408693857866450e-02 +-2.5355485948204657e+00 +-1.0136908332542796e+00 +8.4673934896972461e-02 +-2.4496784250944326e+00 +-1.0010324812158762e+00 +8.5079351202012404e-02 +-2.3183055109599624e+00 +-1.0075251606880151e+00 +8.8450552070963834e-02 +-2.3571842391495821e+00 +-1.1451247976298353e+00 +9.4603289159631121e-02 +-2.3799859975854778e+00 +-7.7903498161367546e-01 +8.7104374885913619e-02 +-2.5953238723057588e+00 +-1.1020975941388584e+00 +1.0402657278843022e-01 +-1.0867318252947133e+00 +-1.0748456057522091e+00 +9.1893583258595146e-02 +-2.3981742508708437e+00 +3.8957106805704600e-01 +7.0689534677358654e-02 +-2.6005214853490251e+00 +-1.1229000733322003e+00 +9.5537167930424702e-02 +-2.2933387464864645e+00 +1.4483840582838505e+00 +6.0858127881665544e-02 +-2.2399530740127216e+00 +-1.0785694487637796e+00 +9.4478353959453670e-02 +-2.3936032407711654e+00 +-1.0901771544207868e+00 +9.5478618835769025e-02 +-2.3964598506800239e+00 +-1.1034834517224565e+00 +9.6099123360220973e-02 +-2.3930093321447266e+00 +-1.1034834517224565e+00 +9.6099123360220973e-02 +-2.3930093321447266e+00 +1.4497093903603031e+00 +6.4521528585247248e-02 +-2.2344677309768937e+00 +-1.2281159637316867e+00 +9.9139171113554247e-02 +-2.3610520254705878e+00 +4.1846697979805503e-01 +8.1372745696408955e-02 +-2.6432632981730366e+00 +4.1284921119020629e-01 +8.2069608259703289e-02 +-2.6291761496934507e+00 +3.4421914586751173e-01 +9.0026118916159845e-02 +-2.5498781697737316e+00 +1.5093430401358108e+00 +7.6666849999170950e-02 +-2.2619478578972894e+00 +5.3100599825733663e-01 +9.0049852035011202e-02 +-2.6414912466986271e+00 +6.3828011411685981e-01 +1.2781638826859387e-01 +-2.7867888969380088e+00 +1.5579536560799179e+00 +1.2978837101054125e-01 +-2.3021925340487059e+00 +-7.1703800804024542e-01 +1.5162402804895259e-01 +-2.7361668587837213e+00 +-7.9935677166116792e-01 +1.5487275964661609e-01 +-2.5847721335873617e+00 +-8.9705334046443030e-01 +1.7084473996814320e-01 +-2.3302411994321193e+00 +1.4662324756439102e+00 +1.5874946664951450e-01 +-2.2138943623858540e+00 +-9.3654992591862918e-01 +1.8345838619910076e-01 +-2.4324066414655188e+00 +-8.5068820075969709e-01 +1.9415448797892151e-01 +-2.5400157313790563e+00 +-9.1284079172437393e-01 +1.9395827432363780e-01 +-2.4505949832711820e+00 +-1.1578921303701832e+00 +2.0240730520245956e-01 +-2.3778398867083772e+00 +-8.0048948673245135e-01 +1.9861536393218635e-01 +-2.3853175051069555e+00 +-8.0218078850686436e-01 +2.0518451581211222e-01 +-2.5805761148851114e+00 +-7.2244900214738084e-01 +2.1189723502085867e-01 +-2.7288131426884172e+00 +-9.0592979679218366e-01 +2.0562119300803550e-01 +-2.3286407171237680e+00 +-9.5092596429292575e-01 +2.1339983465827275e-01 +-2.4838495564904837e+00 +1.0057586829825274e+00 +2.2954309109870372e-01 +-3.1771231198803198e+00 +-1.0052201148793602e+00 +2.1487898361969202e-01 +-2.4730498324070442e+00 +-7.3905910117645812e-01 +2.3584911144769069e-01 +-2.6920661512077930e+00 +1.6828471816417898e+00 +2.3075288775937822e-01 +-2.1579576914799250e+00 +5.3174231170885833e-01 +2.4590046258416867e-01 +-2.6440751198318488e+00 +1.3186127253087003e+00 +2.4613409230375691e-01 +-2.4569539491597485e+00 +-1.1925542706053739e-01 +3.0165811084239291e-01 +-3.3236578970032968e+00 +-1.3850109107667602e-01 +3.0883317827793555e-01 +-3.4718964101143808e+00 +-1.5331613730758195e-01 +3.1946651125255388e-01 +-3.4252760611595563e+00 +-2.6507401032982603e-01 +3.3678252293176941e-01 +-3.6678488671806231e+00 +-8.6514078999503929e-01 +3.4091392340019422e-01 +-3.2538450870819844e+00 +-8.9444485182192790e-01 +2.8607439868742202e-01 +-2.4889463791243349e+00 +-9.6009092189840484e-01 +2.4698173288170999e-01 +-1.6028052005475939e+00 +-8.9494157656155560e-01 +2.8575296001869216e-01 +-2.4548873843203114e+00 +-7.7828947163581819e-01 +2.8343105537439373e-01 +-2.4025063292232391e+00 +-7.9390971202138538e-01 +3.0001554782702661e-01 +-2.5291816925952983e+00 +-8.4546597696852610e-01 +2.9621399301306545e-01 +-2.4802384430880724e+00 +-4.7673546036147241e-01 +3.4406999988573789e-01 +-3.6150979075889444e+00 +-7.8800745078601619e-01 +3.0605866885730965e-01 +-2.5523028394887191e+00 +1.4599648969704830e+00 +3.0715624451439744e-01 +-2.2276608151402035e+00 +2.1457478924857636e+00 +3.3862969159641643e-01 +-2.6484472158450378e+00 +2.1496625780985545e+00 +3.3878912401052835e-01 +-2.6530326048135167e+00 +-8.5724748498017467e-01 +3.0582657119459217e-01 +-2.4051792799049379e+00 +-6.3329456368547410e-01 +3.4123409535833077e-01 +-2.9808011388732090e+00 +-1.0741463172340813e+00 +3.1110901203335140e-01 +-2.3976475129334323e+00 +-9.0208230338606210e-01 +3.1271814809439119e-01 +-2.4486417714298514e+00 +-9.0208230338606210e-01 +3.1271814809439119e-01 +-2.4486417714298514e+00 +-9.0306920279107694e-01 +3.1826864627364732e-01 +-2.4810695719195248e+00 +-9.0345322828336350e-01 +3.1297167023207556e-01 +-2.4115907793987947e+00 +-9.4793777498910237e-01 +3.1826285398013121e-01 +-2.4255406443039522e+00 +-1.0159970445447373e+00 +3.1522647865041442e-01 +-2.3008973810060986e+00 +-1.1433701889175956e+00 +3.2419064104078904e-01 +-2.3803447351809623e+00 +-1.0224839947199650e-01 +3.8571255923836062e-01 +-3.2849392056437035e+00 +-4.7545245825076293e-01 +4.6400891733855670e-01 +-4.2186221672014925e+00 +-1.5963921808537299e-01 +4.2338803087078819e-01 +-3.4303768031766246e+00 +-8.3230075996348707e-01 +3.7214427920553894e-01 +-2.5432696641373611e+00 +-4.2284086734078158e-01 +4.8373680746602471e-01 +-4.1043329926076053e+00 +2.1076144746047589e+00 +4.3377888966179107e-01 +-2.8685753914396104e+00 +-3.3047833659712311e-01 +4.8473745076276620e-01 +-3.8691573345781984e+00 +-3.4428074088026106e-01 +4.7526290813377764e-01 +-3.6568810375280774e+00 +-3.4855062612416066e-01 +4.8119344872932418e-01 +-3.8988649455310851e+00 +-8.9635918152064553e-01 +3.7823628791234970e-01 +-2.4511254410504200e+00 +-1.1391520126484038e+00 +3.7495183093019774e-01 +-2.3786050341222174e+00 +-2.9863451486068049e-01 +4.8890138225609875e-01 +-3.7703637999889339e+00 +-3.1175517521002333e-01 +4.8893616250771577e-01 +-3.6118300953379681e+00 +-1.7507175868884900e-01 +4.9893778560491131e-01 +-3.5990575216260021e+00 +-1.1156149261340194e+00 +3.9820670345155817e-01 +-2.3843170893973316e+00 +1.1267388235312037e-01 +4.5020040205740980e-01 +-2.8850424650428272e+00 +1.7133312169457973e+00 +5.0247476874563513e-01 +-3.0454998209428932e+00 +-4.5005414629185943e-03 +5.3916089113136112e-01 +-3.8060743024932711e+00 +4.5213944273874584e-01 +4.5087844919094755e-01 +-2.6446400038123561e+00 +-7.3136339624499214e-01 +4.3965301676486201e-01 +-2.6983289788809919e+00 +-4.2409607390453974e-01 +5.6284454119830896e-01 +-4.1276165938464064e+00 +1.9665527967446073e+00 +4.9754816433153209e-01 +-2.8084039235772522e+00 +-2.5235609129485642e-01 +5.4492323371717832e-01 +-3.8018273866733732e+00 +1.9321970440426190e+00 +5.1197253918121988e-01 +-2.8433816537392231e+00 +-1.0079785127813379e+00 +4.2837321011673568e-01 +-2.4225463101604179e+00 +5.7878399776845876e-02 +5.0827183365618434e-01 +-3.0864552366431837e+00 +-7.4400086350817116e-02 +5.4788132576994586e-01 +-3.4881620825819111e+00 +-7.3683122764814490e-01 +4.7131794440395591e-01 +-2.6784533094697127e+00 +-1.3674393476436872e+00 +4.4038855882023631e-01 +-2.3912884755566566e+00 +2.2320971937823392e-01 +5.2699536361345967e-01 +-3.0619383971647851e+00 +-8.9239270433786100e-01 +4.6263947020107316e-01 +-2.4494759870729710e+00 +2.6163673304501306e-01 +5.4782259724464188e-01 +-3.0818109260700921e+00 +2.5731874676621858e-01 +5.5208792080616498e-01 +-3.0697357543772248e+00 +-8.9307663966519391e-01 +4.7948374313367853e-01 +-2.4853310084653657e+00 +-1.0991330143912772e+00 +4.7313876340665034e-01 +-2.4218520974719122e+00 +-9.1525876141404572e-01 +4.8831156074971011e-01 +-2.4717240282363786e+00 +-1.2146184505667594e+00 +5.1775627396213808e-01 +-2.6054374789108814e+00 +-8.7588931600639819e-01 +5.0231276884884868e-01 +-2.4960321942081207e+00 +-1.2478369001731919e+00 +4.8724874676178254e-01 +-2.3917211019170894e+00 +-1.0099213317520419e+00 +4.8798426478893725e-01 +-2.3721067516601262e+00 +-9.2152993531400973e-01 +5.0847301652577770e-01 +-2.4650346010468613e+00 +-9.4810917727717259e-01 +5.0912785436428576e-01 +-2.4470793553453936e+00 +-9.0764710398116133e-01 +5.1286729240902029e-01 +-2.4736347163552224e+00 +-9.1509122065361459e-01 +5.1285768509771812e-01 +-2.4658874216125306e+00 +-1.4226623166123080e+00 +4.9860732969020055e-01 +-2.4061863243557355e+00 +-1.0342193837509057e+00 +5.0670600977776326e-01 +-2.4026324404577570e+00 +-1.0342193837509057e+00 +5.0670600977776326e-01 +-2.4026324404577570e+00 +-8.1251862529917351e-01 +5.4945488786003549e-01 +-2.5716654117530169e+00 +-1.8969233085478748e-01 +7.0892753240850492e-01 +-3.8099469530356620e+00 +-1.2520792457139982e+00 +5.6703516107465390e-01 +-2.4760171520116110e+00 +-7.9525790803616558e-01 +6.0204317593663248e-01 +-2.6075157075508733e+00 +-8.9645911611593032e-01 +5.8246684710363117e-01 +-2.3697345182229292e+00 +-1.1239177874922401e+00 +5.8471861030442640e-01 +-2.3812078207374601e+00 +-1.2192436880088156e+00 +6.1531457750977192e-01 +-2.5173709567397453e+00 +-1.2182986154080080e+00 +6.1334450783728367e-01 +-2.4686619253673117e+00 +-8.7789210649309768e-01 +6.3830393973209265e-01 +-2.4965625565519134e+00 +-8.8486352988563011e-01 +6.4603006036100841e-01 +-2.5223812435776796e+00 +-9.7426676125018996e-01 +6.2383094019382246e-01 +-2.3504321218418887e+00 +-8.7430092458126063e-01 +6.6069303944168778e-01 +-2.5038734429558298e+00 +-9.8241905846967625e-01 +6.3021988016352748e-01 +-2.3785494583805575e+00 +-1.0184439050158602e+00 +6.5165637268204157e-01 +-2.4626419528690988e+00 +-1.0305403658973082e+00 +8.0426246686604919e-01 +-3.5379795785895838e+00 +-1.0297884514760745e+00 +6.2449264699650120e-01 +-2.2950395357943738e+00 +-1.0199001088784088e+00 +6.2282492602382500e-01 +-2.2844542970225343e+00 +-1.0590647391649897e+00 +6.3854874556136321e-01 +-2.3802370659940300e+00 +-1.0203748351495388e+00 +6.7001732585846208e-01 +-2.4681504412405779e+00 +-7.9020230595009877e-01 +7.0124263800760012e-01 +-2.6276664781397456e+00 +-1.1331569638331602e+00 +6.5482294714509026e-01 +-2.2778021334818375e+00 +-1.1349464055646692e+00 +6.5637888860411775e-01 +-2.2683766698914170e+00 +-1.2372588117158929e+00 +6.9581266546183107e-01 +-2.5059497820330305e+00 +-1.2480425756347171e+00 +6.9424295776230860e-01 +-2.4967814039214073e+00 +-1.3198659764595837e+00 +6.8061980008753675e-01 +-2.4035361893630891e+00 +-1.2904982875816000e+00 +6.8193245538455705e-01 +-2.4049348917216173e+00 +-1.1351490528237613e+00 +6.7781496508243833e-01 +-2.3595469402122808e+00 +-8.7868227591733006e-01 +7.1731215728830033e-01 +-2.4924348590834060e+00 +-8.6817279914524881e-01 +7.3052856882520700e-01 +-2.6146050061666237e+00 +-1.1156034083707660e+00 +6.9112951097225050e-01 +-2.3679884806622300e+00 +-9.8972222441312041e-01 +7.3352092836993898e-01 +-2.5468965231622378e+00 +-1.1254027862791116e+00 +7.1536544125635937e-01 +-2.3339238832394167e+00 +-1.1262564750041688e+00 +7.5511850262089941e-01 +-2.5710508998012638e+00 +-1.2103408390010335e+00 +7.2715820751769100e-01 +-2.3727539143251684e+00 +-1.2670366110531994e+00 +7.2468306373299451e-01 +-2.3013884107672760e+00 +-1.1989184836648146e+00 +7.8007937607668787e-01 +-2.5672366587796400e+00 +-7.6167302206766407e-01 +8.5994882329462008e-01 +-2.8242814997968697e+00 +-7.9248643857744383e-01 +8.2991745625303104e-01 +-2.6992435860840640e+00 +-1.2387831545598036e+00 +7.7103507547397621e-01 +-2.4013394503328831e+00 +-1.2097734134107674e+00 +7.7826253151923042e-01 +-2.4080771319590104e+00 +-5.7963075573895173e-01 +-1.2817392326329852e-02 +-9.2442733121846001e-04 +-3.7304896280057964e-01 +-3.1491665551202585e-03 +-6.3586391731287084e-01 +4.0886716348310348e-01 +-3.7110330288267060e-02 +-2.5462465011110025e+00 +5.7408647277097402e-01 +-3.0084203288164496e-02 +-2.6812252103046093e+00 +-8.0355825782019463e-01 +1.4928897687808267e-02 +-2.6096411981142151e+00 +-8.1062955195942854e-01 +5.7567980482288228e-02 +-2.3750023309280088e+00 +-8.1514112069003530e-01 +5.7884213249384975e-02 +-2.3706382451320707e+00 +-1.1441382199375052e+00 +9.4256257932394810e-02 +-2.3744616689897660e+00 +-1.1441382199375052e+00 +9.4256257932394810e-02 +-2.3744616689897660e+00 +-1.0250353869668518e+00 +9.7778730288795260e-02 +-2.4191457762834254e+00 +-8.9346730035247501e-01 +1.0306253327363801e-01 +-2.3353950514468198e+00 +1.7034976339004611e+00 +7.5972638528940359e-02 +-2.1388769393205176e+00 +1.3340964321292150e+00 +9.9624911684888476e-02 +-2.4138482572575968e+00 +1.3535732031037815e+00 +1.0256916296130465e-01 +-2.4356638685017225e+00 +2.0019577357233791e+00 +9.8462032393516391e-02 +-2.3179968806088413e+00 +-7.9968124867612944e-01 +1.4562378448016830e-01 +-2.5870323833469326e+00 +2.0641547663718094e+00 +1.2753198149319891e-01 +-2.3865645212144853e+00 +-7.9941474053284500e-01 +1.6984558085401141e-01 +-2.5894818728274807e+00 +-1.2043287144342600e+00 +1.7127161153089690e-01 +-2.3569904096843337e+00 +1.6072838632270281e+00 +1.6139262039566241e-01 +-2.2278081011298871e+00 +1.6320155639970402e+00 +1.6166850637835520e-01 +-2.2208352060252183e+00 +-1.0034105706378709e+00 +1.8066587260908096e-01 +-2.4151097362464951e+00 +-1.0276209015123396e+00 +1.8366928684118969e-01 +-2.4028767371560784e+00 +-8.1319922584504456e-01 +1.9307150793775363e-01 +-2.5657881119014809e+00 +-8.0177522771249576e-01 +1.9349842773235956e-01 +-2.5810906847502748e+00 +6.5600208067416321e-01 +1.9811058356223354e-01 +-2.7821404501417439e+00 +-7.6677076535060418e-01 +2.0129311925121449e-01 +-2.6114292546427156e+00 +2.0629205336388976e+00 +1.8768582934784611e-01 +-2.3840283458031770e+00 +2.0629205336388976e+00 +1.8768582934784611e-01 +-2.3840283458031770e+00 +-1.0620665265969058e+00 +2.0433210250045966e-01 +-2.3946716077115093e+00 +1.5450413174932327e+00 +2.2527134765460910e-01 +-2.2628154940655647e+00 +1.5254658021213983e+00 +2.2720886249665231e-01 +-2.2718868043492315e+00 +-7.4080050995323687e-01 +2.4738760841076607e-01 +-2.6673196522583353e+00 +-7.4080050995323687e-01 +2.4738760841076607e-01 +-2.6673196522583353e+00 +-8.0106544953015635e-01 +2.5159976754260421e-01 +-2.5852203383367884e+00 +-8.0106943630433958e-01 +2.5160437040323863e-01 +-2.5850477201913660e+00 +-8.9897045565111411e-01 +2.4648832242410176e-01 +-2.4588654673465591e+00 +-7.4481663241002194e-01 +2.6819340244703332e-01 +-2.6942515385516193e+00 +-1.0064518688116761e+00 +2.5455011682730055e-01 +-2.3578525864567701e+00 +1.9880186312019663e+00 +2.7504716104137178e-01 +-2.4474954444346442e+00 +-8.9482168357506731e-01 +2.7934565258230976e-01 +-2.4877886009957249e+00 +1.3309030261994432e+00 +2.8138453952520337e-01 +-2.3087102442310523e+00 +-8.8736597761461811e-01 +2.8276263552589870e-01 +-2.4958039798500846e+00 +1.3599181656358696e+00 +2.9046228260187745e-01 +-2.3471993456317617e+00 +-1.1212680310759744e+00 +2.8241946858590816e-01 +-2.3788332928813531e+00 +-7.5673105330036383e-01 +2.9664907691992443e-01 +-2.6482940074024248e+00 +-1.1427487349370000e+00 +2.8489880525740530e-01 +-2.3752360556672651e+00 +-4.0403906872795364e-01 +3.8255709809957428e-01 +-4.0453801318600577e+00 +-1.0597017706536076e+00 +3.1274922145881928e-01 +-2.4015882599532419e+00 +-1.0600211836262190e+00 +3.1574224175765403e-01 +-2.3990926700286703e+00 +5.4665889448610105e-01 +3.4311863481611532e-01 +-2.6579965005216959e+00 +1.5420289787809456e+00 +3.5293014241311171e-01 +-2.6743443761624377e+00 +-1.0157909659252431e+00 +3.2134874156774834e-01 +-2.4164461727124578e+00 +-1.1531876481564776e+00 +3.2060234405314225e-01 +-2.3774981926156262e+00 +-1.1222174425105573e+00 +3.2345040812447906e-01 +-2.3721307245109662e+00 +1.7289714486651830e+00 +3.9836060239411092e-01 +-3.0653392622371873e+00 +1.8938878197148687e+00 +3.9295917158418342e-01 +-2.9121213262104471e+00 +1.9012135626187532e+00 +3.9520209675052431e-01 +-2.9508518804242589e+00 +-2.6964440913074766e-01 +4.2513469631532758e-01 +-3.6766461726186654e+00 +-1.2305649931517521e-01 +4.1602615319858516e-01 +-3.3645535209752815e+00 +-1.5187514361332682e-01 +4.1992802153241543e-01 +-3.4139528577930296e+00 +-1.0838208251516288e-01 +4.2078989972020653e-01 +-3.3144584117122893e+00 +2.0924454496938436e+00 +4.1881233573883098e-01 +-2.7745790696437824e+00 +2.0633899008561145e+00 +4.3160185956389630e-01 +-2.9054524199518332e+00 +3.6442225590816735e-01 +3.8630257712419053e-01 +-2.5489698481315108e+00 +1.9424741054453145e+00 +4.3146338310216059e-01 +-2.8853725094344043e+00 +2.0710339483509861e+00 +4.3177888992381264e-01 +-2.8811415257708943e+00 +-1.7294236723394138e-01 +4.5490203133754653e-01 +-3.4834226734456988e+00 +1.8632154688288125e+00 +4.4583213339039029e-01 +-2.9209521780336187e+00 +-1.0192732560800286e+00 +3.8265508590921965e-01 +-2.4177018083453459e+00 +2.1876151582120373e-01 +4.3317362083873673e-01 +-2.7148010304830477e+00 +-3.1712945001040060e-01 +5.1850484577986022e-01 +-3.8374996522088582e+00 +-1.2087368475761287e-01 +5.0193751971301359e-01 +-3.4707891068064871e+00 +-6.3480218896998386e-01 +4.6023797370152009e-01 +-2.9907343201858012e+00 +-3.8067790530110113e-01 +5.5435167121708195e-01 +-4.0298717641379369e+00 +3.6106274160319268e-01 +4.5985800338215971e-01 +-2.5603518988178471e+00 +-1.0564263659806445e+00 +4.2593454899583494e-01 +-2.4046826551815403e+00 +-1.3692382563574643e+00 +4.2765653570398693e-01 +-2.3987004632041971e+00 +-8.4443837217962840e-03 +2.9353377764564093e-01 +-6.9311736699756477e-01 +-1.0706245514164590e+00 +4.3595921902960361e-01 +-2.4236474479277765e+00 +-3.2105013374336627e-01 +5.7257357985423929e-01 +-3.8258767348245288e+00 +-7.3592361008285034e-01 +4.6707189511671299e-01 +-2.6920570154312489e+00 +-1.5242493000503296e-01 +5.6272955867022545e-01 +-3.6047437524418409e+00 +-2.7938502557541534e-01 +5.8450960940497687e-01 +-3.7350860200391827e+00 +-8.9100642977419786e-01 +4.6005355204002202e-01 +-2.4883373098108414e+00 +-1.3057107456103115e-01 +5.7693533619766935e-01 +-3.5740731619596562e+00 +-1.3020255140980072e-01 +5.8075118345654864e-01 +-3.5693947871940646e+00 +-8.2365039056627043e-01 +4.7891825456144527e-01 +-2.5588677860648907e+00 +-7.9930402385725474e-01 +4.8484104817705570e-01 +-2.5787758555000342e+00 +-8.5062524293213992e-01 +4.7945755172206855e-01 +-2.5305694551374920e+00 +1.6870685633751867e-01 +5.4143951580261429e-01 +-2.8986115138496995e+00 +-7.1099769091416709e-01 +5.0630859476777490e-01 +-2.7147145002155315e+00 +-9.9919424902831833e-01 +4.6130660612979957e-01 +-2.3443181328941010e+00 +-9.5098927983971515e-01 +4.8529636722357783e-01 +-2.4651077871885603e+00 +-1.0242225420976165e+00 +4.4640954331478727e-01 +-2.1866040073851263e+00 +-9.5338862873354357e-01 +5.0406778301849287e-01 +-2.4401149030263318e+00 +-1.3039938311844701e+00 +4.9680735578424745e-01 +-2.3910364612796808e+00 +-7.9819088474571087e-01 +5.2608151699781869e-01 +-2.5458016603245581e+00 +-1.1226594452826135e+00 +5.6017246346463878e-01 +-2.3857324763374215e+00 +-1.2261589442992853e+00 +5.9118638570674642e-01 +-2.6682337167305228e+00 +-7.8361532782078935e-01 +6.0058130837365409e-01 +-2.5998188462812224e+00 +-9.1313857648788177e-01 +5.9872787363011060e-01 +-2.5041639253162113e+00 +-1.1360818951592382e+00 +5.8091946110558668e-01 +-2.3850442641672895e+00 +-7.9687520977642790e-01 +6.2039753486097027e-01 +-2.5685493670138033e+00 +-8.8675827688082665e-01 +6.1588884319992598e-01 +-2.5117541028466461e+00 +-7.4445928792752081e-01 +6.5179745225210095e-01 +-2.6886128493773667e+00 +-7.5201167676833036e-01 +6.5104897862492461e-01 +-2.6657567697719826e+00 +-7.6675363377685835e-01 +6.5341303904013637e-01 +-2.6451361040420602e+00 +-1.3604309619718566e+00 +6.5220912254369201e-01 +-2.4158042386286236e+00 +-1.2723227356141373e+00 +6.5426512890567801e-01 +-2.3990469141989417e+00 +-1.3574452016831382e+00 +6.6078364990095495e-01 +-2.4162085338037516e+00 +-1.2683764254625711e+00 +6.8087835095040872e-01 +-2.5067487884916648e+00 +-1.1175369846635352e+00 +6.6806578733675659e-01 +-2.3826414294067049e+00 +-1.1212365048471913e+00 +6.6830975233691514e-01 +-2.3833485662263443e+00 +-1.2990723117794789e+00 +6.7074799592216172e-01 +-2.4009283220880513e+00 +-9.9549824490424776e-01 +6.8663514567763473e-01 +-2.4305170197610115e+00 +-7.9827512239612131e-01 +7.3943326099775097e-01 +-2.6064573414823662e+00 +-1.2394774781397406e+00 +7.5472514988130412e-01 +-2.5058281833872598e+00 +-1.0112344731968816e+00 +4.9659661695938800e-01 +-1.0089478879440368e+00 +-1.2047075783847192e+00 +7.7615313526577445e-01 +-2.3975639495855470e+00 +-1.2142365904906443e+00 +7.6942675243171177e-01 +-2.3687934929004255e+00 +-1.0845239347526536e+00 +8.4560038778454805e-01 +-2.6448694593666122e+00 +3.4160350281330678e+00 +3.7753898553944776e-01 +-7.5422139021113361e+00 +3.0259888179910821e-01 +-2.2206118797351782e-02 +-8.0108665949374747e-01 +1.5990721770058833e+00 +3.3383357986070929e-02 +-4.1032357408045277e+00 +1.3703168366822087e+00 +1.5441621911092207e-01 +-2.5026567833059628e+00 +3.1742039133856461e+00 +5.3858911671093446e-01 +-7.1567214353717228e+00 +3.1742039133856461e+00 +5.3858911671093446e-01 +-7.1567214353717228e+00 +1.9375340255652405e+00 +-4.5943930159473720e-02 +-4.6129429337379477e+00 +4.4121808814259049e+00 +1.9775225134291119e-01 +-9.0755984625766075e+00 +4.4295557486218522e+00 +2.4652928727319648e-01 +-9.1946430884415005e+00 +3.2370517119140043e+00 +3.6918557433212162e-01 +-7.2105977567770978e+00 +1.3735996919678484e+00 +-3.2180339271691526e-02 +-2.2878337533132114e+00 +1.3735996919678484e+00 +-3.2180339271691526e-02 +-2.2878337533132114e+00 +4.4096641633379914e+00 +3.4949295745547193e-01 +-9.0989258946276301e+00 +4.4722896264791610e+00 +3.5778311439273874e-01 +-9.0178633101658772e+00 +1.3678648898611176e+00 +9.2940109822637465e-02 +-2.3001294986290519e+00 +1.3690358258239042e+00 +-2.6711438965149721e-02 +-2.3138372691973861e+00 +1.5772869558823090e+00 +7.5625348544849549e-02 +-4.0818011736776008e+00 +3.2856182062713173e+00 +3.4026277329093518e-01 +-7.2385690132428060e+00 +1.3802784387653382e+00 +1.9052546003842244e-01 +-2.2920242684896133e+00 +1.8607973291639708e+00 +5.5909081930327398e-01 +-4.7242571082320444e+00 +1.3432681748232325e+00 +6.3687097577175389e-02 +-2.3514151841789586e+00 +1.3443306078294608e+00 +6.3022085368531308e-02 +-2.3540459591532632e+00 +4.2407816520320321e+00 +3.8187315126087162e-01 +-8.8526528351896054e+00 +1.8979470346508476e+00 +3.8357456585310251e-01 +-4.6830029523727585e+00 +1.3463991413339136e+00 +1.9050339480280087e-01 +-2.3412812328160655e+00 +1.3712370025127880e+00 +2.5509585036448268e-01 +-2.3286843689022385e+00 +4.3410688223138703e+00 +3.8998837764857697e-01 +-8.9724164210442350e+00 +3.2430562071877485e+00 +3.3978466585431538e-01 +-7.2177015553430541e+00 +1.3694097239583514e+00 +9.8052535860536000e-02 +-2.3183703053438438e+00 +3.3022861339097891e+00 +4.3523673934341345e-01 +-7.2766754181513154e+00 +1.4027285322984979e+00 +1.3610121739868439e-01 +-2.5676153615718116e+00 +1.3750709321973755e+00 +1.5559317249126803e-01 +-2.3080890581180067e+00 +1.3679754679952800e+00 +-3.4374306370502559e-02 +-2.2925393184541547e+00 +1.3688483450287221e+00 +-3.3871923547306101e-02 +-2.2938655817470432e+00 +1.3560994044956451e+00 +8.4279074281388477e-02 +-2.3269865250886301e+00 +1.7745584248906212e+00 +5.8413925124258135e-03 +-2.1951039098619662e+00 +1.4815178188845093e+00 +2.2870242518116608e-02 +-2.2636864253488889e+00 +1.7794903341470445e+00 +2.7725948243442128e-01 +-4.3196906578294385e+00 +2.7472355941594145e-01 +4.2626598731720228e-01 +-3.4837647914957182e+00 +2.1862956061579797e-01 +3.0521090950472035e-01 +-3.8336962998449660e+00 +-4.5441554548458864e-02 +3.2061998325992686e-01 +-3.2687750344907993e+00 +-4.5441554548458864e-02 +3.2061998325992686e-01 +-3.2687750344907993e+00 +1.9435883747124096e+00 +4.4016222840988894e-01 +-2.9421158996207533e+00 +-1.2587323333787753e-01 +6.0026902730502740e-01 +-3.7273524174875958e+00 +-7.9953125155557037e-01 +-6.9546971335397653e-02 +-4.8119569420001856e-01 +1.6685673053321677e+00 +7.8018553158844721e-03 +-2.1528003818723946e+00 +2.9752843820222710e+00 +1.1685483233129783e-01 +-3.0994715194488238e+00 +2.6353276951671556e-01 +2.0712515063716261e-01 +-3.7582978109694536e+00 +2.6217482390989366e-01 +2.9957480079492066e-01 +-3.7788168038936973e+00 +2.8401757998645510e-01 +3.2476109377553386e-01 +-3.6462404079201476e+00 +2.7737538631306841e-01 +4.1319846210994599e-01 +-3.9714712358326736e+00 +2.0124208728750363e+00 +3.9758227686338038e-01 +-2.8338860320259660e+00 +1.3089801522992078e-01 +5.4984189317384935e-01 +-3.0493060003977837e+00 +-1.1961518446255917e+00 +5.9611332776861321e-02 +6.5113138955170041e-02 +1.5350284847228839e+00 +-7.4724994780737908e-02 +-2.1742375013295230e+00 +1.6077966914459263e+00 +1.8447022667939275e-01 +-4.0536380944895676e+00 +1.5441638699668212e+00 +2.0417198326379932e-01 +-2.2466272757277976e+00 +2.7932339976255988e-01 +2.7448459293398830e-01 +-3.7635372533233906e+00 +-1.2480106970672353e-01 +3.5274036326207525e-01 +-3.4169580465521139e+00 +1.8189589971576410e+00 +4.0001509450641071e-01 +-2.7922816396486669e+00 +2.0006462434467558e+00 +4.1154664499983379e-01 +-2.9468085374474282e+00 +2.0327226386105020e+00 +4.5234567195192116e-01 +-2.9325494094158389e+00 +3.2107347263001940e-01 +5.5408255923591676e-01 +-3.5910263419453248e+00 +4.3029535376939751e-02 +5.1792737224095409e-01 +-3.0868294931463089e+00 +6.3380422667884417e-01 +5.6685909665028256e-01 +-3.3549558547336988e+00 +9.2536552944549733e-01 +-5.6193091024313108e-02 +-3.1387272561767872e+00 +8.3114567127949390e-01 +3.1111697402606872e-02 +-2.9837225692390952e+00 +1.4342722596444799e+00 +1.1292830197607340e-01 +-2.2600329665898280e+00 +1.5492365014647551e+00 +1.9033269461352520e-01 +-2.1480991988297697e+00 +1.9471961443680069e-01 +2.2061626973827642e-01 +-4.3213224543724804e+00 +2.6055125841524152e-01 +2.3301961005812041e-01 +-3.7291031640501502e+00 +2.5038812141440808e-01 +2.6573198854599916e-01 +-4.2733778804448725e+00 +1.0364013715580107e+00 +2.5367478188719977e-01 +-3.2254866718839463e+00 +2.3823432326854319e-01 +2.9423838289996279e-01 +-3.5922847619266403e+00 +2.3823432326854319e-01 +2.9423838289996279e-01 +-3.5922847619266403e+00 +3.0949908143114575e+00 +3.3017826828711938e-01 +-3.2818172674675612e+00 +-1.7727412675173251e-01 +3.5382245775529136e-01 +-3.5080037274919320e+00 +-1.4126185438692945e-01 +3.7751898080666635e-01 +-3.4324800770516255e+00 +-2.3698341864125771e-01 +4.0019751664954423e-01 +-3.6211647318067350e+00 +2.0089782018763431e+00 +4.8752084890566494e-01 +-2.9544427469424610e+00 +5.5331151623699192e-02 +5.2593323865450514e-01 +-3.5606041734646996e+00 +-8.2679985726479699e-01 +-9.2168658308676328e-03 +3.1934428274195686e-01 +-8.2679985726479699e-01 +-9.2168658308676328e-03 +3.1934428274195686e-01 +-7.5681538260443504e-01 +-7.5975305559249348e-02 +-6.3210951721021569e-01 +1.9878488698968162e+00 +-1.0030873877660598e-01 +-2.3524064390574608e+00 +1.5769380321906923e+00 +3.0794573038676189e-02 +-3.9468684686288782e+00 +-1.7494152085149453e-01 +2.9568593354762823e-01 +-3.4925033231773757e+00 +1.3805594776638284e+00 +2.7234136304200507e-01 +-2.2334055091816905e+00 +-8.5723108103959098e-02 +3.3128459905066754e-01 +-3.3486319924546617e+00 +-5.0974305980580704e-02 +3.2785321925035432e-01 +-3.2744378845839766e+00 +1.8013637552282387e+00 +3.8243759864357246e-01 +-4.4521453873554266e+00 +1.9470317507733788e+00 +3.7224758499465088e-01 +-2.9450525924304203e+00 +1.9470317507733788e+00 +3.7224758499465088e-01 +-2.9450525924304203e+00 +2.4938759726426829e-01 +4.4492232093671530e-01 +-4.4681532449393000e+00 +2.7707992895511036e-01 +4.6515022496708508e-01 +-4.0498920502393920e+00 +-2.6158964225834525e-01 +4.8285327515797255e-01 +-3.6511364900391561e+00 +1.2091349637827117e-01 +5.6857329880677354e-01 +-3.1097799323685873e+00 +-1.2485535763665181e+00 +2.7968711207387156e-02 +1.1333271008752277e-01 +-4.3535715226709931e-01 +5.1302812719270653e-02 +-6.6009048020780814e-01 +6.2856688535288796e-01 +-8.2472880938588081e-02 +-2.8821907117964010e+00 +1.9960893622125111e+00 +-1.0409292265067886e-01 +-2.3242590369523599e+00 +2.0105169260461273e+00 +-4.0452403906337045e-02 +-2.3277681687814247e+00 +2.0105169260461273e+00 +-4.0452403906337045e-02 +-2.3277681687814247e+00 +4.3914333169501124e-01 +1.1284721092480018e-01 +-2.8437531091458692e+00 +1.5764628092725090e+00 +1.0214389563092297e-01 +-2.2564710735030484e+00 +2.4646671079638178e+00 +8.6121966919410473e-02 +-2.7253250506452535e+00 +1.6052576712802318e+00 +1.5331172208994004e-01 +-2.2195549642380175e+00 +-1.2705890148946092e-01 +2.1329916361452575e-01 +-7.3228040644500669e-01 +7.0677162007363528e-02 +2.0782985614570446e-01 +-3.9784901242062003e+00 +-1.1317582032699673e-01 +2.4210288912674313e-01 +-7.0289816284701789e-01 +-1.3058196148097037e-02 +2.4477992431311915e-01 +-6.8038225965830001e-01 +2.7206233247289530e-01 +2.4566279742048863e-01 +-3.7037061829031388e+00 +-2.5378983656770621e-01 +3.0978341547295946e-01 +-3.6083990631599603e+00 +1.4638564128213301e+00 +2.8690366061583156e-01 +-2.3180355969982958e+00 +2.0020847566242685e+00 +3.0287588479381350e-01 +-2.4605459813420807e+00 +2.0648925753976921e+00 +4.6178672419532935e-01 +-2.8861169282232662e+00 +2.6706910226550525e-02 +4.5190764436263353e-01 +-3.0618393067660397e+00 +5.3511907925464330e-01 +5.6238323182721051e-01 +-3.2701520104337569e+00 +3.7116453210698802e-01 +5.7187213865222197e-01 +-3.3122088928887146e+00 +-4.3785432452173777e-02 +6.3803809727472360e-01 +-3.7028503064361673e+00 +2.0145595852898222e+00 +-1.1413226322549783e-01 +-2.3321146390277123e+00 +2.0145595852898222e+00 +-1.1413226322549783e-01 +-2.3321146390277123e+00 +1.4760662182967312e+00 +-6.8946588689801580e-02 +-2.2078389189843111e+00 +-1.3804221564448679e-01 +9.8446293733056203e-02 +-7.1482618116957053e-01 +-1.3804221564448679e-01 +9.8446293733056203e-02 +-7.1482618116957053e-01 +7.1169732474967262e-01 +-4.0736497668555735e-02 +-2.8761692773595526e+00 +7.7208749517830899e-01 +-4.4984086769514840e-02 +-2.9435900835440654e+00 +2.0135185780803342e+00 +4.7089087571961771e-02 +-2.3446162919544773e+00 +1.4801021098067131e+00 +1.0276798952786260e-01 +-2.2318839300403366e+00 +9.3557376376775425e-01 +1.6868051641943080e-01 +-3.1151843693319807e+00 +1.6833551610006787e+00 +1.8228623397443280e-01 +-2.1199029143824761e+00 +2.1724956133951784e-01 +2.1810016692159317e-01 +-4.1709182912110245e+00 +-1.5091476113150487e-01 +2.3803286127909870e-01 +-7.1674560207383708e-01 +-8.3838124139855119e-01 +2.5097263377693735e-01 +2.6299254309409953e-01 +1.7026531075603586e+00 +2.3638651114846379e-01 +-2.1072245731357380e+00 +2.3720119239391735e-01 +2.8135543251877088e-01 +-4.1635729234407401e+00 +1.9881344550892660e-01 +2.8698306046611033e-01 +-4.4432921212544692e+00 +9.1399408473439336e-01 +2.9735847784892244e-01 +-3.0853662076620592e+00 +-1.5631662666181845e-01 +3.1107324761800931e-01 +-3.4740199706501529e+00 +1.4712409667564206e+00 +3.0314864016104159e-01 +-2.2802433928266779e+00 +-2.8080422122317489e-01 +3.4928342776430443e-01 +-3.7506675145232120e+00 +2.6655457526179011e-01 +3.5271049882597133e-01 +-3.7018679696970458e+00 +2.6655457526179011e-01 +3.5271049882597133e-01 +-3.7018679696970458e+00 +-8.4039155545006197e-02 +3.8736689351592513e-01 +-3.3231480398700146e+00 +1.9404178350432759e+00 +4.2426838458982197e-01 +-2.9416677988449802e+00 +4.6303047179283857e-01 +4.1505536930374609e-01 +-2.8212712054306155e+00 +-1.7792536063241388e-01 +4.3158808996412823e-01 +-3.5262107494126211e+00 +2.3937141979893978e-01 +4.6251553000315215e-01 +-3.5282364116732281e+00 +1.9211351740071218e-02 +4.4200614983247577e-01 +-3.0650677844245373e+00 +4.4233757763915077e-01 +4.4227615744874238e-01 +-2.7783650603182410e+00 +4.2857832924493838e-01 +4.4160784842052292e-01 +-2.7880403130149660e+00 +2.7518390621814043e-01 +4.7338513860688253e-01 +-3.5827781689682006e+00 +4.7695782523166602e-01 +4.5648658379803647e-01 +-2.7963094102581412e+00 +1.9226279142077712e-01 +5.7099167090107450e-01 +-4.1302345606186046e+00 +7.0380692972422720e-02 +5.4229360220371048e-01 +-3.1200677514183863e+00 +-3.1988449658912421e-01 +5.8295414764865583e-01 +-3.8523360746942852e+00 +4.2914133517765893e-02 +6.3892631753920992e-01 +-3.8216160478625572e+00 +4.1960899961341570e-03 +6.3931471868175194e-01 +-3.8072962500093142e+00 +-6.7589302104421461e-02 +6.6372829402986944e-01 +-3.7905414345345143e+00 +-1.2029930577498056e+00 +5.5673118530446535e-02 +1.3207968329989794e-01 +2.0302323089151484e+00 +-8.4871819707306090e-02 +-2.3583328189556627e+00 +2.0146597599239802e+00 +-6.2481018034067359e-02 +-2.3192315207778456e+00 +1.6493933736014106e+00 +1.2874820664205547e-02 +-2.1538628338834864e+00 +1.4567134172652907e+00 +5.2062901950392329e-02 +-2.3021287342533618e+00 +5.0713066686129871e-01 +1.3148890619060966e-01 +-2.8425259069491502e+00 +1.0382737522682497e+00 +1.1372303357283425e-01 +-3.2298950032128109e+00 +1.5891513254148448e+00 +8.7637535220248600e-02 +-3.9774858506373110e+00 +-4.5689601918008867e-02 +2.0731070149012915e-01 +-6.5456295979606227e-01 +-1.4604958656508160e-01 +2.3484922117204429e-01 +-7.1579371182627105e-01 +-1.5522381002783264e-01 +2.3512883652139432e-01 +-7.1861424880640035e-01 +-3.1965016472064767e-01 +3.0189961678168270e-01 +-3.8714907323723109e+00 +-1.4124458165302745e-01 +3.3207995278293173e-01 +-3.4307494545938604e+00 +4.7149326406093950e-01 +3.2570900362405342e-01 +-2.7749893306151376e+00 +2.6313321691667796e-01 +3.4270414986413106e-01 +-3.6843105053157936e+00 +2.7004218756678317e-01 +3.5163807491614602e-01 +-3.6745348835270946e+00 +2.9984502723208579e+00 +3.4058494439258474e-01 +-3.2180916396518886e+00 +3.0151919493223200e+00 +3.5012681097486570e-01 +-3.1872657355434884e+00 +3.0732473300759375e+00 +3.9008458840029170e-01 +-3.2677261950137204e+00 +3.0536859180420044e+00 +4.0799837428738323e-01 +-3.2206696903452610e+00 +3.1383482765939519e+00 +4.1205792274020847e-01 +-3.3013646410845068e+00 +1.9384725056173828e+00 +4.1779958512640120e-01 +-3.0182849554029652e+00 +2.1139354610791208e+00 +4.2314545378218671e-01 +-2.8983583277466787e+00 +1.9597322044117016e+00 +4.3811641908461363e-01 +-3.0045039676739882e+00 +-1.8499596978742594e-01 +4.5216189078402041e-01 +-3.5711471735525429e+00 +-3.4641468134543207e-01 +5.1708085230032574e-01 +-3.8437791705503264e+00 +4.2349557629929130e-01 +5.6875761202229480e-01 +-3.4015867210342039e+00 +4.1755991779117402e-01 +5.6773015560678508e-01 +-3.3493446212297169e+00 +-2.6772030392735358e-01 +6.3898008830387387e-01 +-3.8441905763439967e+00 +5.8166893266075526e-01 +-9.9115541174614893e-02 +-2.8482245761324974e+00 +1.7064703297361976e+00 +-1.9835361911997815e-01 +-4.1397689961058592e+00 +4.8816285728035297e-01 +-5.9423872920317033e-02 +-2.7805120429075671e+00 +1.4400579902340345e+00 +-7.2172968879352206e-02 +-2.2025557974627534e+00 +1.3883311653741941e+00 +-6.9897025964958268e-02 +-2.2825749947103926e+00 +7.1206907822074839e-01 +-6.4846025165844132e-02 +-2.8654555301017424e+00 +8.3557881598440908e-01 +-6.4624201522729921e-02 +-2.9982726918293956e+00 +1.4525897847053038e+00 +-5.5208141025574399e-02 +-2.2429607472049478e+00 +1.3929932838975130e+00 +-7.9755094164212070e-03 +-2.2851205626448832e+00 +-1.0762395721371713e-01 +1.3316493195382387e-01 +-6.7474610630442644e-01 +5.0267766895692589e-01 +7.6392684048342638e-02 +-2.8351431401498468e+00 +1.6312369498365964e+00 +1.6018843088773443e-01 +-4.0557150526398136e+00 +1.0704531345724648e+00 +1.8415789322542769e-01 +-3.2659909842662671e+00 +9.4849643690156760e-01 +2.0035538543714229e-01 +-3.1153886500278825e+00 +1.1860053410310463e+00 +1.9953262022486279e-01 +-3.4310813581040582e+00 +1.6636505640550610e+00 +2.4453238324581353e-01 +-2.1722153481557300e+00 +5.9501727221226063e-02 +2.8688350307651922e-01 +-4.0880544299727584e+00 +8.4426401663735806e-01 +2.7674391741807425e-01 +-3.0409037096574920e+00 +1.7442951209887472e-01 +2.9161485921479768e-01 +-3.3451276035909605e+00 +-9.0012075051029802e-02 +2.9872721509298783e-01 +-7.0070772231007872e-01 +-1.4657913580155296e-01 +3.6897636210964402e-01 +-3.3770376914801705e+00 +1.9285494642632942e-01 +4.1086891034296802e-01 +-4.2430041047457303e+00 +2.6877568646812428e-01 +4.0168263889466255e-01 +-3.7684397843401718e+00 +3.0304243483818536e+00 +4.0937857435146646e-01 +-3.2805023322208986e+00 +4.5609240623936026e-01 +4.0539017257603804e-01 +-2.7905238363831488e+00 +4.5629336298187873e-01 +4.0508897543397249e-01 +-2.7915323004986474e+00 +2.7354144960423632e+00 +5.2663577509813275e-01 +-6.2623861591010703e+00 +1.7501634150324566e-01 +4.3473585821881905e-01 +-3.2322162509037593e+00 +1.8397601155644105e+00 +5.0107145723089663e-01 +-4.6064809044207031e+00 +1.7676561376325614e-01 +4.5008065711903245e-01 +-3.2487567147954217e+00 +2.5970483036267428e-01 +4.8602615302918412e-01 +-3.6733349957735295e+00 +5.3690785929432083e-01 +4.6112440970768381e-01 +-2.8303968269492406e+00 +-2.8438646500857451e-01 +4.9034060851366751e-01 +-3.7558916482227405e+00 +5.9775295623285996e-01 +5.0251619492570199e-01 +-2.8908599722731441e+00 +-1.8861247396672798e-01 +5.9376390635227760e-01 +-3.7147327701340154e+00 +-1.8861247396672798e-01 +5.9376390635227760e-01 +-3.7147327701340154e+00 +5.1253540400658937e-01 +-4.0246212457748343e-02 +-2.8406699556438122e+00 +7.0992348003640871e-01 +-4.4522823786235656e-02 +-2.8641530083856388e+00 +1.3782601592587245e+00 +-2.1429866094055030e-02 +-2.2752621615354851e+00 +4.7369775291850846e-01 +7.6114411638917662e-02 +-2.8555393801150775e+00 +1.4463685922238858e+00 +6.1400423039528064e-02 +-2.2356277808301948e+00 +-1.2206685643066691e-01 +1.6130587821457801e-01 +-6.9601926310877538e-01 +1.1545032466955825e+00 +6.0462779394477771e-02 +-3.3931729713136534e+00 +-9.4874877364763618e-02 +1.8087634938614691e-01 +-3.6311812335294996e-01 +1.3870970364697257e+00 +9.0154888079325257e-02 +-3.7084479984500733e+00 +1.5826158184765757e+00 +1.2328455941145222e-01 +-2.2046609022486043e+00 +1.5811422198774834e+00 +1.5570037351582025e-01 +-2.2860258015296591e+00 +7.7066228024068417e-01 +2.1687917086061750e-01 +-2.9370872518068181e+00 +-3.7232824579612293e-02 +2.3499585121154476e-01 +-6.7936105833225113e-01 +-1.2369986217949476e-01 +3.8248078201215407e-01 +-3.3932291334405260e+00 +1.9275411794530439e+00 +3.7534535728185597e-01 +-2.9380985619881108e+00 +1.9262284589951078e+00 +3.7482608455487121e-01 +-2.8925259946628947e+00 +1.9398020784496353e+00 +3.8133679182910729e-01 +-2.9361406768595075e+00 +3.0627227303987454e+00 +3.9294269527449954e-01 +-3.1821898112942573e+00 +3.0566653847189267e+00 +3.9884672963004186e-01 +-3.2019626525377953e+00 +2.5362597675976639e-01 +4.1831288991537191e-01 +-4.0325046555841748e+00 +1.7591360918726948e-01 +4.1014158293086611e-01 +-3.2583918174184610e+00 +2.4163077403128386e-01 +4.5365205702152867e-01 +-4.4544267537328581e+00 +1.9182929359424237e+00 +4.5231535433316666e-01 +-2.9744597468342651e+00 +-2.0704605911941054e-01 +4.5626485029393715e-01 +-3.5485856847950483e+00 +2.1415645917051043e+00 +4.9059772624816067e-01 +-2.9004633378308742e+00 +1.9818342783169296e+00 +5.0876622671491478e-01 +-2.9709241194404163e+00 +4.0408154226515836e-01 +5.7607221032506095e-01 +-3.4062061142571167e+00 +2.5614108951105524e-01 +5.8848962768137614e-01 +-3.4927358882363775e+00 +-9.6270744326277502e-01 +-8.7228869232939717e-03 +-1.8506954565627631e-01 +5.8024461725656795e-01 +-1.0418852456552950e-01 +-2.8505304390832511e+00 +6.5508497528556042e-01 +-6.2086327544794498e-02 +-2.8032685366494237e+00 +1.4416858182448209e+00 +-6.5896912016626868e-02 +-2.2429122479558479e+00 +1.6764914289436790e+00 +-2.2003967732424783e-02 +-2.1157558810621984e+00 +-8.7214124139381830e-02 +1.2046226688794333e-01 +-6.6285249394233070e-01 +-1.2785889380496918e-01 +1.5235163920268666e-01 +-6.9375689814700414e-01 +-1.2785889380496918e-01 +1.5235163920268666e-01 +-6.9375689814700414e-01 +9.3459872082644790e-01 +5.0103233169910430e-02 +-3.1480331430118009e+00 +1.4017932962240043e+00 +1.2539550399029551e-02 +-3.7341083798664667e+00 +5.3925863796825058e-01 +7.4465518194596014e-02 +-2.7965282636177977e+00 +-1.2437439128503328e-01 +1.5724735555279523e-01 +-6.9744413500331814e-01 +1.6073186336861582e+00 +6.0787143910011408e-02 +-2.1710679423690986e+00 +1.5982579773403642e+00 +6.2046812050011127e-02 +-2.2346945640543963e+00 +1.5973116695701284e+00 +6.1890637251467054e-02 +-2.2621931359562053e+00 +1.5589997564018301e+00 +7.2307554488120845e-02 +-2.1992293788799282e+00 +1.6085972233998111e+00 +8.4141877806671511e-02 +-2.1750638670964411e+00 +6.1669066241128778e-01 +1.5077953001186212e-01 +-1.2346472934645785e+00 +1.4442503103332631e+00 +1.5543768287091747e-01 +-2.2574051288705732e+00 +1.4461355695840268e+00 +1.6180718967726879e-01 +-2.2368932153372887e+00 +1.4484147746923226e+00 +1.6281566327283123e-01 +-2.2567850987697673e+00 +1.6890849937606247e+00 +1.6952844410620277e-01 +-2.1183822333038340e+00 +1.4612322980170307e+00 +1.8336146437755599e-01 +-2.2525737119348959e+00 +1.5737256475882040e+00 +2.1335904060861569e-01 +-2.2848389461981324e+00 +1.5594307655287742e+00 +2.1383433561522319e-01 +-2.3046326884597335e+00 +1.5717202429330628e+00 +2.1601914132877406e-01 +-2.2605694986396467e+00 +1.5717202429330628e+00 +2.1601914132877406e-01 +-2.2605694986396467e+00 +1.5433566375868846e+00 +2.1992190341486600e-01 +-2.2871423191576814e+00 +1.5654569219586285e+00 +2.2177687159430773e-01 +-2.2982918367882039e+00 +1.5654569219586285e+00 +2.2177687159430773e-01 +-2.2982918367882039e+00 +1.5352037907486296e+00 +2.2516850693277790e-01 +-2.2498497412702854e+00 +1.5542980727713562e+00 +2.2514744296535080e-01 +-2.2726259354229672e+00 +1.5722414293527491e+00 +2.2409110794294324e-01 +-2.3012699465682722e+00 +1.5548760943916313e+00 +2.2408358114422799e-01 +-2.2998809681579617e+00 +1.6181095911903702e+00 +2.4294587024612946e-01 +-2.2500596318865216e+00 +1.6636538038703628e+00 +2.4308997878523850e-01 +-2.1659166523534688e+00 +8.6995897283257051e-01 +2.4913656803941017e-01 +-1.3455463789311117e+00 +1.5682713025157011e+00 +2.4579510496857954e-01 +-2.2848816476782052e+00 +1.4638363902151592e+00 +2.8279372630650540e-01 +-2.2532249266200632e+00 +1.4536519298384334e+00 +2.8336548955598639e-01 +-2.2521024910002985e+00 +1.9967568841859187e+00 +2.9015619012809313e-01 +-2.4612350593240535e+00 +2.8267840903402802e-01 +3.2831456164026912e-01 +-3.6926688990761023e+00 +6.3177934837370975e-01 +3.1453775272318024e-01 +-2.8059434773595524e+00 +-1.0568421762123084e-01 +3.1259050351326750e-01 +-7.2111470206647887e-01 +6.3732251258483485e-01 +3.7157598257417096e-01 +-2.8014009988621371e+00 +6.2964833695386069e-01 +3.8313660520178044e-01 +-2.8423450042113108e+00 +3.0662335541080079e+00 +4.0233810383973517e-01 +-3.2246259584103618e+00 +2.1530855310987027e+00 +4.2657965510120593e-01 +-2.8444791399948435e+00 +2.0333238425457227e+00 +4.3494840686161512e-01 +-2.9715529752738186e+00 +2.2100386992037548e+00 +4.7610254861376194e-01 +-2.7459785379278676e+00 +2.0667291658586011e+00 +4.9197576967307671e-01 +-2.9244276744172164e+00 +2.0525599918991282e+00 +5.1455365514455387e-01 +-2.9232526522395923e+00 +4.4055554057449537e+00 +7.1100598117482372e-01 +-4.9507248820744394e+00 +4.4055554057449537e+00 +7.1100598117482372e-01 +-4.9507248820744394e+00 +-1.6934645434105480e-01 +5.8990726270087453e-02 +-6.8263075283933383e-01 +6.9349656993772935e-01 +-4.5934763362134208e-02 +-2.8580625049258441e+00 +6.9355060568865834e-01 +-4.3052182035668338e-02 +-2.8555321531777258e+00 +1.4058116613878073e+00 +6.9701569565836466e-02 +-2.2923916744487647e+00 +1.6904387052145555e+00 +6.5387460238595985e-02 +-2.1171252519501298e+00 +1.5786502107196052e+00 +9.4252405651389870e-02 +-2.2776940589805026e+00 +1.3770373634901036e+00 +9.9884843208865690e-02 +-2.3210358863700047e+00 +7.4766880462502183e-01 +1.1468745577671281e-01 +-2.8986917196548778e+00 +1.6209690017255001e+00 +1.2407998464307611e-01 +-4.0183360935254990e+00 +1.4256924799393522e+00 +1.8951392388829549e-01 +-2.2649746491813816e+00 +1.1812823804986883e+00 +2.0581780655329268e-01 +-3.4220304978634859e+00 +1.5823498043903679e+00 +2.0553820330843184e-01 +-2.2076918604743758e+00 +1.5979391252839634e+00 +2.1350142036686531e-01 +-2.2763151221878934e+00 +1.5776796241764903e+00 +2.1540780293907152e-01 +-2.2613034111829009e+00 +1.5735849319482011e+00 +2.2003805562271431e-01 +-2.2582827080897907e+00 +1.5735849319482011e+00 +2.2003805562271431e-01 +-2.2582827080897907e+00 +1.5781868866732216e+00 +2.2214006816650000e-01 +-2.2943436132394539e+00 +1.5624222907441654e+00 +2.2206279058872344e-01 +-2.2774993493070110e+00 +1.6077066822797799e+00 +2.2202858372001849e-01 +-2.2911054864068126e+00 +1.5730638873103970e+00 +2.2437990074815853e-01 +-2.2579076392154214e+00 +1.5931139872616717e+00 +2.2420256881232528e-01 +-2.2796778729670173e+00 +1.5689556950470924e+00 +2.2463518318664280e-01 +-2.2621452740811945e+00 +1.5725363769509186e+00 +2.2543859440778954e-01 +-2.2615094522929589e+00 +1.5828821352590183e+00 +2.2785807847274223e-01 +-2.2992525949160876e+00 +1.5853490989755594e+00 +2.2981088449412265e-01 +-2.2481192686039542e+00 +6.1015993073079400e-01 +2.4768189145295139e-01 +-2.7734953693845608e+00 +1.8586841042518754e+00 +2.3533791467076531e-01 +-4.4318657562227699e+00 +6.2350838543226650e-01 +2.5059125131943732e-01 +-2.7962986646432078e+00 +5.9195850484258061e-01 +2.5197193929677825e-01 +-2.7635801898974184e+00 +8.8345987564678186e-01 +2.6285787934783622e-01 +-3.0423161518185773e+00 +9.6041854454946307e-01 +2.6290136459574615e-01 +-3.1451207291931960e+00 +1.6068762472184850e+00 +2.5086450942519695e-01 +-2.3050239529074825e+00 +1.4503181101328122e+00 +2.5784186112477447e-01 +-2.2859271823529443e+00 +7.3241740502899455e-01 +2.7135949960534822e-01 +-2.9018984426675560e+00 +2.0360258121290618e+00 +4.3393102189261917e-01 +-2.9783799243393272e+00 +2.1324415868710629e+00 +4.5017599763054633e-01 +-2.9235481817650109e+00 +2.9868665141514743e+00 +6.0071389336489078e-01 +-6.6855877148418017e+00 +2.0345856099071642e+00 +4.5897514313733206e-01 +-2.9890513765839888e+00 +2.1377355761723580e+00 +4.5929651635757074e-01 +-2.9293685531840965e+00 +2.0559627035198647e+00 +4.9258769410095876e-01 +-2.9273269328507858e+00 +2.0576795643102694e+00 +4.9565692084260693e-01 +-2.9252138419992040e+00 +1.5695008080302901e+00 +3.6909612518960438e-01 +-6.6334047310317301e-01 +1.4673680178906250e+00 +1.2398281554706832e-01 +-9.3258737540288283e-01 +1.5091293531827958e+00 +1.2231687214578947e-01 +-9.5803716920499282e-01 +1.4574769299916004e+00 +2.7635954712570626e-01 +-9.4393941907185563e-01 +1.4734664082450522e+00 +4.4934644022544479e-01 +-6.7755416891550457e-01 +1.4901976793078950e+00 +7.3984850250225137e-02 +-8.8541777218939077e-01 +1.5562461646069736e+00 +8.7822538408738188e-02 +-5.7980796094067877e-01 +1.5047842809937622e+00 +1.2695245005678557e-01 +-8.4650282057768378e-01 +1.4660619837308848e+00 +1.2963085115366868e-01 +-7.2946996759783866e-01 +1.5653912130457623e+00 +1.7082145396658699e-01 +-5.8581179720127441e-01 +1.3625882809611072e+00 +2.1690383373846456e-01 +-9.3520776591389243e-01 +1.3691982019936098e+00 +2.1289041605773262e-01 +-1.0549156064264236e+00 +1.4915520714449806e+00 +2.2193348988021566e-01 +-9.3553473668452680e-01 +1.4807369775336436e+00 +2.2306778883605602e-01 +-9.2866595858045276e-01 +1.5006354532936008e+00 +2.2557665190494827e-01 +-8.4773783091649646e-01 +1.5130731189218043e+00 +2.2625775707317022e-01 +-7.6261936840490019e-01 +1.5733533273109679e+00 +2.6500751269289424e-01 +-5.9271841638722256e-01 +1.4981909403083551e+00 +3.9722623111980593e-01 +-1.1915062556517027e+00 +1.5882963766704161e+00 +4.2259020640167250e-01 +-4.8864288282000440e-01 +1.3930391190443774e+00 +1.7244855549737792e-01 +-1.0167224232246299e+00 +1.4166425181615103e+00 +1.7190847149476746e-01 +-1.0340446668629855e+00 +1.4869229882284565e+00 +1.7544841443091988e-01 +-8.8457425974918535e-01 +1.5052328488978173e+00 +1.7689383305530645e-01 +-7.0981195454783030e-01 +1.5052328488978173e+00 +1.7689383305530645e-01 +-7.0981195454783030e-01 +1.5041305810795556e+00 +1.7606818200351648e-01 +-8.0116633209255117e-01 +1.3654335159386413e+00 +2.6911295993296119e-01 +-1.1066908312495356e+00 +1.4811849725376689e+00 +2.6846903063594846e-01 +-8.8203075642112549e-01 +1.5732734470617400e+00 +2.5573747264517777e-01 +-5.3780490066273945e-01 +1.5444846021696654e+00 +2.7251774774691478e-01 +-7.3590139231999963e-01 +1.4944779179318164e+00 +2.6852686947488963e-01 +-7.0832251532468682e-01 +1.5267033794541474e+00 +2.7063023533770197e-01 +-8.1909255177875018e-01 +1.5468240081729110e+00 +3.2202123052109993e-01 +-6.2837330353233178e-01 +1.5497887676556277e+00 +3.3871910661901156e-01 +-5.8249889546711175e-01 +1.5497887676556277e+00 +3.3871910661901156e-01 +-5.8249889546711175e-01 +1.4986044857635903e+00 +3.6865929296981509e-01 +-8.9651236092024567e-01 +1.4565445942255466e+00 +3.7417596771645567e-01 +-9.2124989563439463e-01 +1.4632032848093324e+00 +3.7511123241041805e-01 +-9.2504858942555857e-01 +1.5247030242762281e+00 +3.6935115462890256e-01 +-7.2321239591101127e-01 +1.4980253874483325e+00 +3.9083127845587956e-01 +-8.4933872012247769e-01 +1.5539415731840820e+00 +3.8379835371659954e-01 +-6.9107572093993841e-01 +1.5586163612077668e+00 +3.8499125394552669e-01 +-6.9367000875682849e-01 +1.5220073929427897e+00 +3.8997462519433429e-01 +-7.7101135977138646e-01 +1.5202504348531245e+00 +3.8880598774447500e-01 +-7.6941891406953200e-01 +1.5335568710754341e+00 +8.5234270041614740e-02 +-8.2249337403820610e-01 +1.3601031901076801e+00 +1.2093269491982110e-01 +-1.1655822842084709e+00 +1.3771862781718613e+00 +1.2522722360268465e-01 +-1.0522947360292216e+00 +1.5227791010474956e+00 +1.3175427127604925e-01 +-7.2152218732804552e-01 +1.5227791010474956e+00 +1.3175427127604925e-01 +-7.2152218732804552e-01 +1.3689371684056202e+00 +2.2418452220026075e-01 +-1.0867869830453074e+00 +1.4837951197935342e+00 +2.2458788045148745e-01 +-8.7813925058351106e-01 +1.5100735206373630e+00 +2.2594894124615492e-01 +-8.0620638345406226e-01 +1.5315919943384175e+00 +2.2869080633032954e-01 +-7.2893698601004586e-01 +1.3578007534094994e+00 +2.6474618443460740e-01 +-1.2106923692588467e+00 +1.3889892958364418e+00 +2.6548994638063694e-01 +-1.0145734322439841e+00 +1.5722009585978198e+00 +2.5577978212092523e-01 +-6.4276615346995425e-01 +1.3730882061643730e+00 +2.9177011549926457e-01 +-1.0499848369428293e+00 +1.5179107357668660e+00 +2.9800622818777922e-01 +-7.6661421289776277e-01 +1.4549741053399876e+00 +3.8274692587989806e-01 +-1.0555326343706708e+00 +-1.2257061102311158e+00 +4.5692753791143759e-01 +-2.4275222147453719e+00 +1.5863516674224640e+00 +4.2052799839089178e-01 +-6.0069930076841815e-01 +1.4098971380680929e+00 +3.5169183152273810e-03 +-1.2060770507066789e+00 +1.3715124508132090e+00 +2.6990079706345712e-03 +-1.1758298779532801e+00 +1.4212214891298538e+00 +6.2854132187897996e-02 +-8.8681220740588784e-01 +1.3926298133476489e+00 +8.2016193686599570e-02 +-1.0573170746086278e+00 +1.4095840890793165e+00 +8.2500994744364925e-02 +-9.8144523520657734e-01 +1.5902357722711264e+00 +1.3604991846922368e-01 +-2.2418828542410747e+00 +1.4408974526745415e+00 +1.7559404678280877e-01 +-9.0278939070652764e-01 +1.3655902146839243e+00 +1.8875114989519820e-01 +-1.1726936134252262e+00 +1.5055178124675250e+00 +1.7667078561951971e-01 +-7.5687035287855553e-01 +1.3601081007514342e+00 +2.7953007522764439e-01 +-1.1711168760916919e+00 +1.3634904502929333e+00 +2.8047206114080581e-01 +-1.1731999167687257e+00 +1.5690671278006689e+00 +2.8026735844806583e-01 +-6.1458304696118182e-01 +2.1206594246691362e+00 +4.6183064086481534e-01 +-2.7681364592762789e+00 +1.3927578410751191e+00 +3.4070745321936707e-01 +-1.1320693340419203e+00 +1.3688828406904847e+00 +3.3980368221923724e-01 +-1.1124514424923804e+00 +1.5304494801544319e+00 +3.6213114170960198e-01 +-7.7350445815977320e-01 +1.5496601351336565e+00 +4.2810077134794272e-01 +-6.7699743805431511e-01 +1.5496601351336565e+00 +4.2810077134794272e-01 +-6.7699743805431511e-01 +-8.2772491506586207e-02 +1.1040855758962236e+00 +-7.0894726868621138e-01 +1.3470598064322477e+00 +-7.7589368443967488e-03 +-1.2075933888949626e+00 +1.3807970516885735e+00 +5.3426526348616925e-03 +-1.2658066056495927e+00 +1.3522548330973561e+00 +5.4547327196156053e-03 +-1.2425231053481756e+00 +1.3576285631251219e+00 +3.2704972896214143e-02 +-1.2515705610520413e+00 +1.6736214654225463e+00 +5.4884537642983199e-02 +-2.1589727166532109e+00 +1.4896774005264868e+00 +6.1673655148343130e-02 +-7.4337578423394590e-01 +1.3751940912651444e+00 +1.2716338874018870e-01 +-1.0023651153053790e+00 +1.3943287006713692e+00 +1.2498183842655186e-01 +-1.0170258669641261e+00 +1.3602432949962655e+00 +1.5949711086130186e-01 +-1.1145164557556457e+00 +1.3602432949962655e+00 +1.5949711086130186e-01 +-1.1145164557556457e+00 +2.5171907990228584e+00 +2.2546745508889712e-01 +-2.3679305201553418e+00 +1.4126747837183480e+00 +2.7029911949366847e-01 +-9.8112369483500628e-01 +1.4156106778257453e+00 +2.8823388143297857e-01 +-9.5470437795334417e-01 +1.4211385321465351e+00 +2.9184763931053892e-01 +-1.0502928511142406e+00 +1.3703194324990624e+00 +3.0579061354211035e-01 +-1.0911374960396534e+00 +1.5702724690455314e+00 +3.8231685964971929e-01 +-5.8977641742294273e-01 +-1.0335315817653199e+00 +4.5276254915759750e-01 +-2.4912027129948835e+00 +1.5265735605524446e+00 +4.4545877950314638e-01 +-8.6303070514967850e-01 +1.5505991919524256e+00 +4.4561879801816995e-01 +-7.8639390836522005e-01 +1.5780146544192601e+00 +4.5127224694149348e-01 +-8.4819576360030324e-01 +1.5646399234653658e+00 +4.4415229925852462e-01 +-6.6061206758212343e-01 +-1.2464663671606770e+00 +5.7250311328492764e-01 +-2.5174507904856633e+00 +-1.1916787906952828e-01 +1.1125635557442672e+00 +-7.2445183535794044e-01 +1.3772929989268692e+00 +-6.5564941023412522e-03 +-1.1314545327580527e+00 +1.3592341397451595e+00 +-6.7020966472592092e-03 +-1.1177601678439197e+00 +1.3620854057499432e+00 +2.1415788983418334e-02 +-1.0953486560617698e+00 +1.3720063541688237e+00 +3.1746197628984861e-02 +-1.1795010728723396e+00 +1.3557148731135926e+00 +4.2881973901370225e-02 +-1.1122731482162731e+00 +1.3531312584654258e+00 +1.1047344329377419e-01 +-1.2441688472785579e+00 +1.6186254394431590e+00 +1.4762340556544518e-01 +-2.2200728546133495e+00 +2.5186898061254088e+00 +1.8390994172341030e-01 +-2.3064502801714459e+00 +2.5186898061254088e+00 +1.8390994172341030e-01 +-2.3064502801714459e+00 +3.3311614934411651e+00 +2.4995838276004539e-01 +-3.3745226440957126e+00 +1.3586066621046116e+00 +1.9468748536056302e-01 +-1.1157025243319136e+00 +1.3559948926947329e+00 +1.9459523734588419e-01 +-1.1143599089430918e+00 +1.7575124984059685e+00 +2.4790155160368971e-01 +-1.4794553701842317e+00 +1.1426421802353421e+00 +2.7210276865538652e-01 +-5.3545241902243512e-01 +-4.0826627511947128e-01 +4.2602785075433208e-01 +-3.4919171196223191e+00 +1.4339253429169023e+00 +3.4591998013064101e-01 +-1.3346000936057105e+00 +1.5703551450162854e+00 +3.0633068663267704e-01 +-5.9865947624683891e-01 +1.5703551450162854e+00 +3.0633068663267704e-01 +-5.9865947624683891e-01 +1.4951194890183745e+00 +2.9983377620741652e-01 +-4.6230759758372708e-01 +1.4538460208168797e+00 +3.0262974537226933e-01 +-4.1610850713315012e-01 +1.5341409463284783e+00 +3.5471930147230002e-01 +-6.9544315057244677e-01 +1.7750588558918304e-01 +5.4820756287176564e-01 +-3.0170755408480048e+00 +1.5122017135896451e+00 +4.2943026855690319e-01 +-9.2490363685221832e-01 +1.4949442052756317e+00 +4.2686343510669916e-01 +-8.6922813781096597e-01 +1.5621222906666667e+00 +4.1242228821449273e-01 +-6.5535777102852200e-01 +1.5200002590372086e+00 +4.2786769824915022e-01 +-7.9212098704266487e-01 +1.5412653941521657e+00 +4.2796831484834830e-01 +-7.1333393232378717e-01 +1.5721273779021736e+00 +4.4647026588190869e-01 +-6.4152876070046561e-01 +1.6082586839588815e+00 +5.0883806011346844e-01 +-9.9941099985127424e-01 +-1.1676154705412098e+00 +6.7837216154763647e-01 +-2.3434510767385297e+00 +-1.3374736010623185e+00 +7.5074396351806005e-01 +-2.5897968205325159e+00 +-3.4625165319193810e-02 +1.2868838340008157e+00 +-7.6220365624439346e-01 +1.3418270682960016e+00 +-3.7743318470844979e-02 +-1.2313268752759770e+00 +1.3645949681152267e+00 +-3.3531908556178422e-02 +-1.1981514972117862e+00 +-1.5296086713820395e-01 +7.9020861888795133e-02 +-7.1932478870077154e-01 +1.4361090898361428e+00 +3.5948110449157973e-02 +-9.2043670108393072e-01 +1.7105904118439652e+00 +2.9025337497097788e-02 +-4.1698203429818603e+00 +1.3735227411409388e+00 +4.6604215988449493e-02 +-1.2310185244215539e+00 +1.4521038101475456e+00 +4.3257797810607936e-02 +-7.1311410694285149e-01 +1.4541479649914348e+00 +4.6463322305250992e-02 +-6.3931897838870588e-01 +2.4636699496402379e+00 +2.7378421622316042e-02 +-2.3489925628659885e+00 +-8.4088324893781197e-01 +9.2600079253175080e-02 +-2.5299519571251774e+00 +1.4267101752610838e+00 +5.9229436066597897e-02 +-6.3226224325773372e-01 +1.3602743860510884e+00 +1.3218404519242127e-01 +-1.1162051630977117e+00 +1.5538972657716221e+00 +1.2002687783468451e-01 +-6.0011245495337306e-01 +1.3739019848826213e+00 +1.4022852678761968e-01 +-1.0722759895540779e+00 +1.3739019848826213e+00 +1.4022852678761968e-01 +-1.0722759895540779e+00 +1.3519258673483623e+00 +1.5264599470845838e-01 +-1.1915510389668527e+00 +1.3634142913002816e+00 +1.7486251736793071e-01 +-1.1007459272445377e+00 +1.3544023223755757e+00 +2.3354511996158112e-01 +-1.1404998335283518e+00 +1.3568896634439893e+00 +2.4828646839364663e-01 +-1.1441691511706737e+00 +1.3617242572076453e+00 +2.5783785945020088e-01 +-1.2505111634061057e+00 +1.3559804519389858e+00 +2.9752309504178026e-01 +-1.1109565361198943e+00 +1.3552486267996129e+00 +3.1041848208509576e-01 +-1.2049902420017666e+00 +1.5123126315420143e+00 +2.8905441465888165e-01 +-7.8923057359655424e-01 +-8.3002677772585864e-01 +3.6542686895346782e-01 +-2.6358769960084691e+00 +1.3875889714730660e+00 +3.2366313415467707e-01 +-1.0949397300521744e+00 +-3.7084376519852136e-01 +4.5335271860476328e-01 +-3.6225939125224453e+00 +1.3949306103376360e+00 +3.4649924745228294e-01 +-1.0188363262352240e+00 +1.3949306103376360e+00 +3.4649924745228294e-01 +-1.0188363262352240e+00 +-3.0685410081920061e-01 +6.1217262530739924e-01 +-3.8876420531867617e+00 +-1.2064195634469685e+00 +4.3422792447859337e-01 +-2.4859675310008194e+00 +1.4870421733141213e+00 +4.3426868685715952e-01 +-9.2714243003301300e-01 +1.5764020098934979e+00 +4.3568416808328747e-01 +-6.2274873112348816e-01 +1.5286515485961094e+00 +4.7904803802804624e-01 +-9.4362119965308500e-01 +-8.5095122940447021e-01 +5.7973224375451060e-01 +-2.5754695554925049e+00 +-9.4749981093764968e-01 +5.6408969281027221e-01 +-2.3687746435043144e+00 +-9.7148389748059083e-01 +6.9588751341170729e-01 +-2.2968095296631725e+00 +-1.1887509769728257e+00 +7.7883647507447118e-01 +-2.3949885311606796e+00 +-1.1887509769728257e+00 +7.7883647507447118e-01 +-2.3949885311606796e+00 +-1.3149165458327372e-01 +1.1055683494269690e+00 +-7.4455925363447795e-01 +-6.4226516848020360e-02 +1.2286136566401995e+00 +-7.3590517478289963e-01 +-2.5399388405654799e-01 +-2.7378992959060217e-03 +2.2309720050622897e-01 +1.3900744921555823e+00 +-3.4224286254650627e-02 +-1.1197176603261967e+00 +1.3673257486485135e+00 +-1.7964724026213640e-02 +-1.1573015099235837e+00 +1.3681651313410692e+00 +-5.0709867697605673e-03 +-1.2178425515172338e+00 +1.3469141709584778e+00 +-4.7802446557249044e-03 +-1.2010266652502781e+00 +1.3508490875098029e+00 +2.7270837494552887e-02 +-1.1213718473709537e+00 +1.3623850440017575e+00 +3.2161093791230159e-02 +-1.2203628387478300e+00 +1.3791914797883094e+00 +6.5750505218339042e-02 +-1.1954090225585188e+00 +1.3606887665509779e+00 +6.6063352831696634e-02 +-1.1581264078049942e+00 +1.3526274617402232e+00 +7.5865043961791084e-02 +-1.1635993828588134e+00 +2.0387963850569535e+00 +1.3601703950343902e-01 +-2.3564849653662550e+00 +2.8909663609997391e+00 +1.4827740495243966e-01 +-2.7479773307929976e+00 +-7.6311877756796964e-01 +1.6961773189465182e-01 +-2.8631058612367446e+00 +1.3702626005143401e+00 +1.3795603165729498e-01 +-1.0871255466395198e+00 +1.4117761292812196e+00 +1.4076799156944933e-01 +-9.4473585171350549e-01 +1.3982861377221607e+00 +1.4423109014790458e-01 +-1.0023444039614677e+00 +1.3982861377221607e+00 +1.4423109014790458e-01 +-1.0023444039614677e+00 +1.3472589393898475e+00 +1.5045579911316009e-01 +-1.2269816211425248e+00 +1.4153730892932608e+00 +1.4498892049542661e-01 +-9.6037718278645434e-01 +1.4046389776132364e+00 +1.6598941010678828e-01 +-1.0927069668704565e+00 +1.3862073044523380e+00 +1.6596790731522046e-01 +-1.0350754127252146e+00 +1.3996303088030797e+00 +1.6730085621550583e-01 +-9.9708096891880871e-01 +1.4473755565096718e+00 +1.6927242933713504e-01 +-9.9056284991260246e-01 +1.0715760303062276e+00 +2.5578374478327626e-01 +-3.2888752074618175e+00 +1.4342273284357752e+00 +1.9731714526592659e-01 +-9.6600317070106734e-01 +1.3617237185040669e+00 +2.1223501396356995e-01 +-1.2605490656936089e+00 +1.3785739034109941e+00 +2.1446427188352374e-01 +-1.2751057127405367e+00 +1.3773207624864501e+00 +2.9657987582071271e-01 +-1.2334776480658083e+00 +1.3773207624864501e+00 +2.9657987582071271e-01 +-1.2334776480658083e+00 +1.3762296443185451e+00 +2.9253807371062662e-01 +-1.0753595802125457e+00 +-7.5636390632928951e-01 +3.7356241865660017e-01 +-2.6661077892681053e+00 +-4.0806930242004574e-01 +5.0589054526914445e-01 +-3.7191824575123884e+00 +1.5187547035789521e+00 +3.3867217155228274e-01 +-7.9105000788065938e-01 +1.3850682466166293e+00 +3.7171521380253902e-01 +-1.2346996282834750e+00 +1.3850682466166293e+00 +3.7171521380253902e-01 +-1.2346996282834750e+00 +1.5363708054571079e+00 +3.3955941578845372e-01 +-7.1736384665991670e-01 +1.5299067721847381e+00 +3.3900217846809172e-01 +-7.1434744691787766e-01 +1.9769696570113326e-01 +5.2170765737449432e-01 +-2.8609837421119444e+00 +-1.0673901899322416e+00 +4.2933097856249491e-01 +-2.4654386512639221e+00 +-9.2768280999514530e-01 +4.7883686466443048e-01 +-2.5223963000152958e+00 +1.5723249837952558e+00 +4.6687131035515939e-01 +-7.2992338240163368e-01 +-8.1489105520475880e-01 +5.7780213826737559e-01 +-2.5213164440910654e+00 +-7.7279705415294275e-02 +1.1216386140998917e+00 +-7.4009421227101824e-01 +-9.3071608343841011e-02 +1.1228218224246991e+00 +-7.4596645263772765e-01 +-6.5047815570762002e-02 +1.2008585992137100e+00 +-7.6265646164233747e-01 +-7.6523314150112029e-02 +1.2054697138625941e+00 +-7.5870504916341919e-01 +-7.2133749757855692e-02 +1.2202808700290213e+00 +-7.6296644641435085e-01 +-6.3859604302183584e-02 +1.2413673775526348e+00 +-7.7876656280672707e-01 +-3.6936805490345448e-01 +5.2716593349480404e-03 +-7.5337875310519742e-01 +5.9220905975941707e-01 +-7.3090070400318632e-02 +-2.7206635591768702e+00 +1.5992954202368941e+00 +-4.4993089828981224e-02 +-2.2014040541939535e+00 +1.3535669570928655e+00 +-1.5824378156374507e-02 +-1.0911484459943379e+00 +1.3741945899229933e+00 +-6.1028463039557238e-03 +-1.2430382813377128e+00 +1.3555937281809143e+00 +-4.8901602676243786e-03 +-1.1881766396482860e+00 +-1.4881202359565548e-01 +6.7306940478687363e-02 +-7.0308927261077203e-01 +-1.5996078966732816e-01 +6.8308793530822684e-02 +-7.0257256574781146e-01 +2.0346990513408096e+00 +-2.7654803789612530e-02 +-2.3536560898616572e+00 +1.3482007566600893e+00 +7.9079897940165147e-03 +-1.0870468043929624e+00 +1.3837997955084163e+00 +6.1740865718419892e-03 +-1.1129293250203116e+00 +1.3540704221154369e+00 +1.5641918856591552e-02 +-1.0792844379385853e+00 +1.3690062379946957e+00 +2.2112505395361814e-02 +-1.2118438508533169e+00 +2.0156809691538933e+00 +9.0217001563609039e-03 +-2.3535247452548318e+00 +1.3582385299505648e+00 +3.2361836844384026e-02 +-1.0947888696905677e+00 +1.3352403140883602e+00 +3.1640060767875545e-02 +-1.1242043048914383e+00 +1.4498900877111229e+00 +4.1400360713239159e-02 +-9.4533870686971444e-01 +-8.4527456113213592e-02 +9.0561931067204088e-02 +-6.6229581429956008e-01 +1.5377392686359876e+00 +4.4429261883730413e-02 +-6.3505948921553390e-01 +1.5497856629761506e+00 +4.5005561250075168e-02 +-5.9395880419382407e-01 +1.3892406524579184e+00 +5.9903115632592881e-02 +-1.2735388063116082e+00 +1.5674758607861639e+00 +5.0034343957519094e-02 +-5.7315514335052820e-01 +6.3606485165317672e-01 +8.9074343749771134e-02 +-2.7747517397392683e+00 +1.4362570375900623e+00 +6.9192838421677422e-02 +-9.6541456954358151e-01 +1.3788773316903755e+00 +8.2440302209275701e-02 +-1.0698680967794734e+00 +1.5634434907759429e+00 +9.3144840396089779e-02 +-2.2291981234681773e+00 +2.5717352593756364e+00 +5.6226711939102142e-02 +-1.0324927375000001e+00 +1.5688001988735534e+00 +8.6276862615258382e-02 +-5.7416662235673410e-01 +2.5292038309527807e+00 +1.3827440710353123e-01 +-2.3017595439047320e+00 +3.0122959514013621e+00 +1.5850924302614866e-01 +-3.1852344283839433e+00 +1.3547114415840076e+00 +1.4012661631695342e-01 +-1.2273159167954411e+00 +3.0541709189660429e+00 +2.1670549559177982e-01 +-3.2056816742495262e+00 +1.5456768760888464e+00 +1.5851994311150569e-01 +-6.5096198259612559e-01 +1.5456768760888464e+00 +1.5851994311150569e-01 +-6.5096198259612559e-01 +2.4992378397111823e+00 +2.1095719405591706e-01 +-2.3404344854458241e+00 +1.3726120160693782e+00 +1.8384946190994053e-01 +-1.0597119266215871e+00 +1.3721906314371282e+00 +1.8318812139162299e-01 +-1.0592782460072878e+00 +1.0485561973093529e+00 +1.8288780789348896e-01 +-7.3513738662301953e-01 +6.7666234241801315e-01 +2.6538589246956129e-01 +-2.9343457600946694e+00 +1.3538603040309591e+00 +1.9956189330089441e-01 +-1.1287758712113671e+00 +1.3531243843581640e+00 +2.3764190053195766e-01 +-1.1373789998668458e+00 +2.0770921201255810e+00 +3.2057177591952235e-01 +-2.4703834427413871e+00 +1.3557554678644013e+00 +2.3956582783679553e-01 +-1.0467691353771102e+00 +1.3838124610515785e+00 +2.4144052120170545e-01 +-1.0420319874222723e+00 +1.0851791873878887e+00 +2.5141777455534609e-01 +-9.8727480364390596e-01 +1.4084247666617953e+00 +2.5106501976906537e-01 +-9.6287372186919884e-01 +2.2266297317508990e+00 +2.5700294711262572e-01 +-9.1817455589118480e-01 +1.3719905081364483e+00 +2.9128037251614924e-01 +-1.0869714648089952e+00 +1.4294332173159736e+00 +3.2112153370981328e-01 +-1.3229592961398591e+00 +1.4363210276678144e+00 +3.1163941302394405e-01 +-1.0723724526281382e+00 +1.3912520277827098e+00 +3.2217966921245000e-01 +-1.2448008417022154e+00 +1.3585086673919506e+00 +3.4138666972629689e-01 +-1.2139023183952167e+00 +1.3585086673919506e+00 +3.4138666972629689e-01 +-1.2139023183952167e+00 +1.3935943357057838e+00 +3.4742140507790020e-01 +-1.1658940777225055e+00 +1.4459026901108951e+00 +3.6991340725480848e-01 +-1.3459114501320315e+00 +1.3726627667662294e+00 +3.4804685470709784e-01 +-1.0955938755033197e+00 +1.4977097460418121e+00 +3.2987115228285802e-01 +-8.3352332256554762e-01 +1.5126283052949312e+00 +3.3039864443241362e-01 +-7.7658986257567741e-01 +1.4151666658742179e+00 +3.7688678397762038e-01 +-1.3043867094172414e+00 +1.5515538088707492e+00 +3.5724432977156900e-01 +-8.0788213028699041e-01 +1.4560072725429829e+00 +3.8259456139571701e-01 +-1.0315997280122380e+00 +1.4360504050075618e+00 +4.1012642393022231e-01 +-1.1387591132009729e+00 +-1.2440321736033426e+00 +4.8108840967679473e-01 +-2.8000107851843814e+00 +-8.5352014979750346e-01 +5.9590179215896610e-01 +-3.4850231608111106e+00 +-2.8546362080675874e-01 +5.8776062357607339e-01 +-3.2271305757113944e+00 +1.5321519341904322e+00 +4.2160319348432107e-01 +-7.7518808679163320e-01 +1.5148933254185108e+00 +4.3043976717864885e-01 +-7.7395435834238002e-01 +1.5526467395328638e+00 +4.2994613063597970e-01 +-6.7325118070517320e-01 +1.5278165591779846e+00 +4.6598680621323418e-01 +-8.8599846309549057e-01 +1.5139105787091220e+00 +4.6314980085476293e-01 +-7.8863933758724725e-01 +1.5528243167288702e+00 +4.6765042555113062e-01 +-8.1071799573955072e-01 +1.5553338264278107e+00 +4.6626636444984076e-01 +-7.7098982895548696e-01 +1.5716010581146029e+00 +4.6872793328057227e-01 +-7.5036751955307668e-01 +1.6023249845207528e+00 +4.4782394730629876e-01 +-4.6162271221320295e-01 +1.5805368646802898e+00 +4.4756639694799721e-01 +-4.5484258416153733e-01 +1.5574485236071449e+00 +5.5029052009688462e-01 +-6.3060583102341561e-01 +-6.8006156775429441e-02 +1.0441896193413172e+00 +-8.0311326693933160e-01 +-5.9684698603161279e-02 +1.1185337130677249e+00 +-7.1894043591012391e-01 +-6.8999521873177747e-02 +1.2852475007317372e+00 +-7.6783983231728925e-01 +-5.2142362173847150e-02 +1.3026680152091741e+00 +-7.5290272809398939e-01 +-3.9761956465578507e-01 +-1.5967204964046865e-02 +-7.6569256717088341e-01 +-3.8776469196513702e-01 +-9.0883701130716477e-03 +-7.5488338111219322e-01 +-3.8776469196513702e-01 +-9.0883701130716477e-03 +-7.5488338111219322e-01 +1.3701024437387528e+00 +-4.7386398520418087e-02 +-1.1971086021254920e+00 +1.3640706396652411e+00 +-2.0712845169186426e-02 +-1.2147056667789340e+00 +1.4355982723962242e+00 +-1.8803787614854326e-02 +-1.0054855017239659e+00 +1.3614084182841593e+00 +-1.7606455831425151e-02 +-1.1233296247404467e+00 +1.3688462313010958e+00 +-1.6267972180746344e-02 +-1.0673539071355531e+00 +-1.1521993949043163e+00 +-9.4469349696926913e-03 +-3.7271803270297021e+00 +1.3609205442453214e+00 +-1.0095547467732476e-02 +-1.0833638574114115e+00 +-1.1176195853887811e+00 +3.3750256768922224e-02 +-2.3879394990398639e+00 +1.3689950480553505e+00 +1.8774542181874666e-02 +-1.2807640488810894e+00 +1.3762715354591659e+00 +2.4267085755778472e-02 +-1.1514492928499978e+00 +6.2710783820613314e-01 +3.8066392368471237e-02 +-3.0447828594139197e+00 +-8.5174378148651719e-01 +7.3749792817973170e-02 +-2.5690925984772819e+00 +1.4512627773824265e+00 +4.3345823636416446e-02 +-9.0113168547350375e-01 +1.3919775727518611e+00 +4.8308608558080751e-02 +-1.2149586229429874e+00 +-8.2837935439289867e-01 +8.4522201425856452e-02 +-2.5193760405226908e+00 +1.5584869589199564e+00 +4.5932867011828263e-02 +-5.5968006428912098e-01 +1.5584869589199564e+00 +4.5932867011828263e-02 +-5.5968006428912098e-01 +1.5584869589199564e+00 +4.5932867011828263e-02 +-5.5968006428912098e-01 +1.3543927587603370e+00 +5.6918731308285217e-02 +-1.1879505659983736e+00 +1.5624008598428782e+00 +5.1271618991720364e-02 +-5.5452371235862818e-01 +1.3576504010278034e+00 +7.3748704716369615e-02 +-1.1878145029871872e+00 +1.4130260562611081e+00 +8.4967134479504991e-02 +-2.2832728000785307e+00 +1.1173319076229546e+00 +9.8769456264601138e-02 +-3.4020497895863766e+00 +1.5595995991423879e+00 +9.3971577108496088e-02 +-2.2046604150054749e+00 +1.3533609028935092e+00 +8.6914859690746818e-02 +-1.1854150919745128e+00 +1.7065716359216072e+00 +9.4172453465082254e-02 +-2.1410794280022047e+00 +1.4903012059139906e+00 +1.1818402848776878e-01 +-3.8655586074443375e+00 +5.3509276150718921e-01 +1.4560388793383472e-01 +-2.9716211591320523e+00 +1.5566866260279171e+00 +9.9042293781994223e-02 +-5.9888387883390870e-01 +2.5111113833739300e+00 +1.1338686690822794e-01 +-2.2727464921485083e+00 +6.0631005378736447e-01 +1.5991066682001126e-01 +-2.9311867441129067e+00 +5.8314949708845176e-01 +1.5976320394878246e-01 +-2.9538488336534030e+00 +1.3601398486417697e+00 +1.2290918064494095e-01 +-1.1584262729187298e+00 +2.9995103294648957e+00 +1.4223111721182355e-01 +-3.1827970401617502e+00 +1.0236316397867493e+00 +1.7147343963997719e-01 +-3.2716384856093366e+00 +2.5012503682590399e+00 +1.4900018432255616e-01 +-2.3090283625515404e+00 +1.6921279895076478e+00 +1.8148357058872633e-01 +-2.1293614912788335e+00 +1.3651098971504672e+00 +1.6742393033663688e-01 +-1.0674473348868045e+00 +1.4984379183699081e+00 +2.3364669164882398e-01 +-2.2410157196921734e+00 +1.4144637330145720e+00 +1.8705896752234197e-01 +-9.3442087007581265e-01 +1.3600501966218019e+00 +2.0243598125842246e-01 +-1.1549578124516033e+00 +1.3862935751977452e+00 +2.0471257950045249e-01 +-1.1687486302004906e+00 +8.8222905382048133e-01 +2.4671838519837849e-01 +-1.6602218300393292e+00 +5.3386453999899142e-01 +2.9534604674754894e-01 +-2.6661676085233048e+00 +1.3616825188332615e+00 +2.4367718709131936e-01 +-1.2487270765495162e+00 +1.3516190324793378e+00 +2.4167618861875281e-01 +-1.1681516982140832e+00 +1.3885107923241748e+00 +2.3900938451773507e-01 +-1.1296428678884056e+00 +2.9571459044013162e+00 +3.5832678246940619e-01 +-3.1970897741438131e+00 +1.3807389904441592e+00 +2.5165542080988357e-01 +-1.2694752294905614e+00 +1.5411515836395449e+00 +2.5741154943824562e-01 +-1.3649162938350656e+00 +1.4876531719220365e+00 +2.1807418119591312e-01 +-6.2001320272757843e-01 +1.3818262460637571e+00 +2.4155934812637989e-01 +-1.0238914619399970e+00 +1.4871491911211339e+00 +2.1809720914262004e-01 +-5.8646766674685691e-01 +1.3842310519701835e+00 +2.4130112566135078e-01 +-9.8708301597753789e-01 +1.3959663267141416e+00 +2.4967273048433511e-01 +-1.0992505519004703e+00 +1.3757597499647305e+00 +2.9586887970378273e-01 +-1.1985750352348994e+00 +1.3989941815244844e+00 +2.8887093011536413e-01 +-1.0127093652314039e+00 +1.5305960935262852e+00 +2.8599792842204208e-01 +-6.9789584248989289e-01 +-8.8853013978720152e-01 +3.5829193501413731e-01 +-2.3339279804110156e+00 +-8.7815410327608356e-01 +3.7560650253751371e-01 +-2.5741582312856366e+00 +1.3899862846495246e+00 +3.4475651094394877e-01 +-1.2624327797637691e+00 +1.3593404267560925e+00 +3.4429953163042637e-01 +-1.2267297516338560e+00 +5.6452663908065392e-01 +4.4518631090824173e-01 +-2.7966810242901494e+00 +1.5813952643164648e+00 +2.9709364769537566e-01 +-4.5239083198848562e-01 +8.8679039640932877e-02 +4.2903157407749903e-01 +-2.6732466910702932e+00 +1.4789326245753298e+00 +3.2693480725785967e-01 +-8.7304477534804625e-01 +1.3868956792266991e+00 +3.5391305098177483e-01 +-1.1708723974410067e+00 +2.3883852018115981e-01 +4.7589793338865832e-01 +-3.0481880108651787e+00 +-7.3541987115666119e-01 +4.0837603228213215e-01 +-2.6421299177779018e+00 +1.5586076792765726e+00 +3.2528638169145790e-01 +-6.7304287997037160e-01 +1.3958624528231034e+00 +3.8100629093194355e-01 +-1.0775716788335730e+00 +1.3683157080466946e+00 +3.8651584626156837e-01 +-1.1128849369472928e+00 +-8.0816352240475975e-01 +4.5940516751614652e-01 +-2.6059445663080001e+00 +-8.0816352240475975e-01 +4.5940516751614652e-01 +-2.6059445663080001e+00 +1.4817694858249211e+00 +3.8743235572874485e-01 +-7.6893248112205759e-01 +-8.9615622553914998e-01 +4.5719034925554131e-01 +-2.5344248284768329e+00 +-8.9105180728606215e-01 +4.6418314988862297e-01 +-2.5689142274853713e+00 +1.5511449572377516e+00 +4.1033225308396415e-01 +-6.3872463365202026e-01 +1.5409456722822388e+00 +4.3120925311887326e-01 +-6.5916757617760757e-01 +1.5117698573692617e+00 +4.6550332922312621e-01 +-9.2657182359329260e-01 +1.5613255031264703e+00 +4.4970715421445823e-01 +-6.0817407488160058e-01 +1.5731665345463111e+00 +4.4878335437857925e-01 +-5.2620462864593454e-01 +-8.5601311869618246e-01 +5.5842102129505922e-01 +-2.5747447997495065e+00 +1.3884718177943907e+00 +5.3778289389079315e-01 +-1.2693254918851731e+00 +1.6613575737520991e+00 +4.8689021050047748e-01 +-6.7750575208782171e-01 +1.5748656268300949e+00 +4.7651092562676595e-01 +-5.8350846464603634e-01 +2.0762467845591948e+00 +5.2773235159664533e-01 +-7.9658118186121751e-01 +1.5452076029826411e+00 +4.9244598732388728e-01 +-6.7876126497590128e-01 +-8.1808855905258193e-01 +6.2042187479341226e-01 +-2.6182911622569729e+00 +-8.0031730545537494e-01 +6.4921077910005898e-01 +-2.6514247759174259e+00 +-9.2204809072410487e-01 +6.2744929974651686e-01 +-2.5442359825106293e+00 +-1.1256246250534490e+00 +4.5280820538974709e-01 +-1.3463752915736871e+00 +-1.0661340684044913e+00 +7.0598751815254734e-01 +-2.5615761625175062e+00 +-8.9018649859543730e-01 +7.0394613070455392e-01 +-2.4500613978950581e+00 +-7.6195595959894197e-02 +1.0088854493687929e+00 +-7.5130499453572452e-01 +-1.1582040073593775e-02 +1.0366805221599460e+00 +-7.4072956715445848e-01 +-7.5790001439448335e-02 +1.2099324559476967e+00 +-7.5328511078245508e-01 +-6.8941818305104305e-02 +1.2424603102242580e+00 +-7.8574313307908261e-01 +-7.3857599402759613e-02 +1.2458927580264367e+00 +-7.8200489064015855e-01 +-7.0305911558139089e-02 +1.2895481788793288e+00 +-7.6028087286058110e-01 +-6.1087673700741522e-02 +1.2961052795056494e+00 +-7.6970652944699713e-01 +-6.4842372628446235e-02 +1.3002188371009020e+00 +-7.6636687039258822e-01 +1.3686327839161834e+00 +-9.5065931667412153e-03 +-1.2678088384911521e+00 +1.3557052559906291e+00 +-6.1825065481828064e-03 +-1.0939248530406012e+00 +1.3733787155976249e+00 +-4.8223230896851091e-03 +-1.0668343546732848e+00 +1.3627844492885344e+00 +-3.3430385341338973e-03 +-1.0919107343255885e+00 +-1.3038640852855954e-01 +7.1914394565632742e-02 +-7.3567788049361693e-01 +1.3475438508272475e+00 +1.1772169312371192e-02 +-1.1383299562904028e+00 +1.3425086960896657e+00 +2.1659494210106312e-02 +-1.2168366510569140e+00 +1.3765877724065929e+00 +2.7517579990220677e-02 +-1.2061433508612409e+00 +-8.0616358116887432e-01 +7.7541315924445145e-02 +-2.5324739961845322e+00 +1.3678639040378813e+00 +4.7112264157606311e-02 +-1.2668560148085262e+00 +1.3592997409385017e+00 +4.6276377891709769e-02 +-1.2613732504999282e+00 +1.3593237290998257e+00 +5.3894883348073484e-02 +-1.2604957263652348e+00 +-8.9111399829162430e-01 +9.5213076548663747e-02 +-2.5776283501943857e+00 +5.0263853752952958e-01 +8.3385876846414811e-02 +-2.7801816472514225e+00 +8.7152869215592788e-01 +1.4703189137386038e-01 +-3.0192249194576535e+00 +1.5589375305770397e+00 +1.3668326316722296e-01 +-2.2899615517680512e+00 +1.4546228152979708e+00 +1.0876699953757679e-01 +-7.0622074439122007e-01 +7.8671338056257589e-01 +1.9482490810738215e-01 +-3.0369136693005490e+00 +5.1376851468649010e-01 +1.9464278696350043e-01 +-2.9322557919905643e+00 +2.5343374375096546e+00 +1.7781313116390687e-01 +-2.2852136261843987e+00 +1.3785067073463282e+00 +1.7191793173904030e-01 +-1.2680885772030921e+00 +-8.2276093485680346e-01 +2.0917803156122980e-01 +-2.3847386496002998e+00 +-8.7985926902617217e-01 +2.1123277720461847e-01 +-2.4174878795064845e+00 +1.3585862818503556e+00 +2.0185805117108074e-01 +-1.1835137258528075e+00 +1.3741721225050536e+00 +2.0211392419315874e-01 +-1.1967002290975535e+00 +1.4330987202995338e+00 +2.2195789830129553e-01 +-1.0861291346540687e+00 +1.3863538415657268e+00 +2.2267590784588365e-01 +-1.0200173222620377e+00 +1.3863538415657268e+00 +2.2267590784588365e-01 +-1.0200173222620377e+00 +1.3651561678182569e+00 +2.3960488697376403e-01 +-1.2646159104270074e+00 +1.3545925913840742e+00 +2.3322023216841753e-01 +-1.1169247391225980e+00 +2.9376202896454702e+00 +3.4742317046560345e-01 +-3.1571444832073685e+00 +1.4189544675961023e+00 +2.2952750548643452e-01 +-9.8070752066904787e-01 +3.0090694041153911e+00 +3.6002042728268630e-01 +-3.2050922768226036e+00 +3.0116347006046742e+00 +3.6031075741809110e-01 +-3.2077879361251451e+00 +3.0295131738076613e+00 +3.6144580198554344e-01 +-3.2086042202266185e+00 +1.3609682143693849e+00 +2.5368205349289297e-01 +-1.1843586866347953e+00 +1.3547162363225898e+00 +2.5244613185819292e-01 +-1.1801242309467659e+00 +2.8326084303020377e-01 +3.1897504975420554e-01 +-2.6770344628013745e+00 +1.4088047727187496e+00 +2.4335689845012057e-01 +-9.3208175274859495e-01 +5.7329676216891701e-01 +3.3267927972333722e-01 +-2.7593671402336941e+00 +-5.1947127664450876e-01 +3.5987654401866553e-01 +-3.3334894036731897e+00 +1.4073231662255361e+00 +2.4881364983125032e-01 +-9.3813844241135325e-01 +1.4099494466789231e+00 +2.4919697704889635e-01 +-9.5418596231669595e-01 +-3.7805557401403928e-01 +3.7453132670669009e-01 +-3.7595801109205409e+00 +3.0118210152037443e+00 +4.0489824997371587e-01 +-3.2035238742128405e+00 +3.0186749447161376e+00 +4.0805201440844652e-01 +-3.2358314287842420e+00 +3.0171760280102502e+00 +4.0692109128555093e-01 +-3.1820501813260336e+00 +2.2243738507849073e+00 +2.5529984738313433e-01 +-7.7911744695523277e-01 +1.3786364263441340e+00 +2.8785984429570360e-01 +-1.2082365888725026e+00 +-1.6286588212370370e-01 +2.2795207026542338e-01 +-6.0489450815915902e-01 +1.3559731667272188e+00 +2.9318908145380573e-01 +-1.2403395975795555e+00 +1.3801307287144009e+00 +2.9705409851523107e-01 +-1.1730011665585369e+00 +2.0833714526966394e+00 +4.4494332007396514e-01 +-2.9359662736887167e+00 +5.9060445539308337e-01 +4.0901407724744865e-01 +-2.8289104485063565e+00 +5.6878724974017014e-01 +4.0546141924983581e-01 +-2.7841483281998629e+00 +1.3802030404765271e+00 +3.3317350160693893e-01 +-1.2436921856528067e+00 +3.6854838398400597e-01 +4.0599583893653146e-01 +-2.5631965543545183e+00 +-8.0065662427159390e-01 +3.6150657280491294e-01 +-2.5068667231510520e+00 +5.7141367375144358e-01 +4.3015552509419058e-01 +-2.7138454801562033e+00 +1.3644381703711628e+00 +3.3449663327661289e-01 +-1.1386554855101181e+00 +3.3457919931875418e-01 +4.3461697156345375e-01 +-2.5808295295685317e+00 +3.3457919931875418e-01 +4.3461697156345375e-01 +-2.5808295295685317e+00 +1.3506282887772059e+00 +3.5213551334262333e-01 +-1.1602487904001766e+00 +1.5160363843429145e+00 +3.2890446135231094e-01 +-7.9270781907136489e-01 +4.8516778698707419e-01 +4.5815909958257905e-01 +-2.7857411248054533e+00 +1.5795566746958747e+00 +3.1635589237721423e-01 +-5.7546654359660632e-01 +1.5277594562655368e+00 +3.2931713927747591e-01 +-7.4794548275625572e-01 +1.3881897863934525e+00 +3.6410994484714054e-01 +-1.2286426684933220e+00 +1.5752846170726582e+00 +3.1664664753600380e-01 +-5.2311504583390578e-01 +1.5293248258309944e+00 +3.2883605469829391e-01 +-6.9365662297178521e-01 +7.4841619427590683e-02 +5.4122490707454374e-01 +-3.6863776844759655e+00 +-8.4794161962047754e-01 +4.2080307410938522e-01 +-2.5894148167725315e+00 +-8.6251168379996557e-01 +4.0985995476006265e-01 +-2.3579138905848316e+00 +-8.0202230211303405e-01 +4.4216256878550575e-01 +-2.6100288738433228e+00 +-6.2960591184238676e-02 +5.5514230641912488e-01 +-3.5396043168168854e+00 +-1.9078735301536015e-01 +5.4909960552104509e-01 +-3.4309096314028045e+00 +-1.0050832127499076e+00 +4.1962788263615669e-01 +-2.3566642249052858e+00 +1.5512472617505264e+00 +3.9425094516830694e-01 +-6.5807983114301627e-01 +-8.1501483090471449e-01 +4.8674277713396752e-01 +-2.5993732023430738e+00 +-5.2587695441102450e-02 +3.3397631854038273e-01 +-6.9442861835976177e-01 +1.5563785479404211e+00 +4.1952016696275135e-01 +-6.6945932450427037e-01 +1.5240777135327803e+00 +4.7065729985130950e-01 +-9.6427535753641147e-01 +-7.5872439991749385e-01 +6.0427147186774555e-01 +-2.6768718588123881e+00 +-6.9201545284612698e-02 +1.0951423716130912e+00 +-8.4182614262583999e-01 +-8.5267662599802674e-02 +1.1145039053416734e+00 +-7.1725608362503568e-01 +-4.3734874312552012e-02 +1.2138003300323681e+00 +-7.3300507280130944e-01 +-6.6815461188750466e-02 +1.2337347393123292e+00 +-7.8329000217360623e-01 +-6.6815461188750466e-02 +1.2337347393123292e+00 +-7.8329000217360623e-01 +-3.7223464798772604e-01 +2.2714563237204773e-03 +-7.5546158786893070e-01 +-3.7223464798772604e-01 +2.2714563237204773e-03 +-7.5546158786893070e-01 +8.1586448536653144e-01 +-1.2635690344955541e-01 +-3.1655116065720597e+00 +5.8091300615320141e-01 +-9.6475275935775345e-02 +-2.7116226680963593e+00 +5.7148004873994740e-01 +-8.5661469021625608e-02 +-2.7046187115792839e+00 +-3.8333735264571722e-01 +4.4588469937179340e-02 +-7.5821105112209930e-01 +-3.8333735264571722e-01 +4.4588469937179340e-02 +-7.5821105112209930e-01 +7.4520157801853026e-01 +-6.6933746079106696e-02 +-3.1061904992339366e+00 +-6.7230195944056229e-02 +2.5602090361852584e-02 +-1.1875861726950878e+00 +1.3919772629990406e+00 +-3.7822890507214622e-02 +-1.1196300055729966e+00 +1.3814627678425353e+00 +-3.2549319192093674e-02 +-1.1399622003445289e+00 +1.3798331931768455e+00 +-2.9479691935190389e-02 +-1.1326070108144171e+00 +1.4068690025911761e+00 +-3.3084096408820360e-02 +-1.1525714695210267e+00 +7.9033704240070868e-01 +-5.0621183901997019e-02 +-3.1423931845956585e+00 +1.3555554693216605e+00 +-2.8535546485091257e-02 +-1.0907730521338632e+00 +1.3458439498479737e+00 +-2.1809233421806743e-02 +-1.2123674261570054e+00 +1.4614942940273272e+00 +-2.0511101797044431e-02 +-2.2245864190336340e+00 +1.4486987485194815e+00 +-1.8982872399938490e-02 +-2.2229086547218282e+00 +6.4209989655803168e-01 +1.0791129803353154e-03 +-2.8853224087543223e+00 +1.5140091334445553e+00 +-1.1798289018515803e-02 +-2.1429748671961804e+00 +1.3730992067654622e+00 +2.6767170874339271e-02 +-1.0820077976967526e+00 +7.5699562855157321e-01 +3.5718738013398886e-02 +-3.0697513277514346e+00 +1.4258692700407620e+00 +2.9706059229402965e-02 +-1.0170610978076475e+00 +1.3799399025567098e+00 +3.1371037026282397e-02 +-1.2877900527743198e+00 +7.0671204608455218e-01 +3.8767013186493171e-02 +-3.0345497336410285e+00 +6.3512610348446352e-01 +3.9608355274710454e-02 +-3.0573580153713777e+00 +-8.5460842817091442e-01 +7.6813420764700865e-02 +-2.4030033783656717e+00 +1.4775660972075200e+00 +3.6384366645611795e-02 +-9.5294813448335902e-01 +-9.1514358220352876e-01 +9.3664122688583443e-02 +-2.2650875539266040e+00 +1.4970970740076901e+00 +4.2381329446969485e-02 +-7.2738742787316779e-01 +2.4888667337272756e+00 +1.7421378064176162e-02 +-2.2932865098051010e+00 +-9.1647099353176842e-01 +8.7747676763176796e-02 +-2.4352275295630297e+00 +1.5052862695841154e+00 +4.4145506203801976e-02 +-6.7377790069917276e-01 +1.3513012161018036e+00 +5.4300101690414271e-02 +-1.2296088473590285e+00 +1.3513012161018036e+00 +5.4300101690414271e-02 +-1.2296088473590285e+00 +2.0173741329052213e+00 +4.5998833228360035e-02 +-2.3759735702893319e+00 +1.4611015224119890e+00 +1.0090958645450405e-01 +-3.8509098935581099e+00 +-8.2458332314809246e-01 +1.3159704768443625e-01 +-2.3795600613611056e+00 +2.6102193355314194e+00 +1.2048342058250402e-01 +-2.6778920368908934e+00 +2.6211764344366490e+00 +1.2109081858938374e-01 +-2.6885836459471486e+00 +-7.8264812641585646e-01 +1.6388731897845182e-01 +-2.5927673320108986e+00 +6.6054742973779390e-01 +1.7416976359271025e-01 +-2.8719940573200096e+00 +1.5621586632791471e+00 +1.1631515677401857e-01 +-5.9697877699306368e-01 +5.7071013918897140e-01 +1.8210715392077556e-01 +-2.7169164013727767e+00 +6.4031625552641991e-01 +1.8943716183125739e-01 +-2.9449579139858018e+00 +8.2583755778362355e-01 +1.9116494347310481e-01 +-2.9559066801917671e+00 +8.2583755778362355e-01 +1.9116494347310481e-01 +-2.9559066801917671e+00 +5.1434241788700985e-01 +1.9393700541280959e-01 +-2.9356962440436369e+00 +8.7767526288976139e-01 +2.0002674599984877e-01 +-3.1202947307439333e+00 +1.0167755377001719e+00 +2.0904903061896699e-01 +-3.2002649700664070e+00 +1.4117601850133723e+00 +1.9122896789173710e-01 +-2.2730892157612921e+00 +1.3817002110582504e+00 +1.9129505256571197e-01 +-2.2360602424020306e+00 +1.4313693997028805e+00 +1.9142381769540681e-01 +-2.2572267121147447e+00 +1.4298894333181646e+00 +1.9128613968363128e-01 +-2.2559243746861117e+00 +1.4273114868474583e+00 +1.9176802572024912e-01 +-2.2172607842298562e+00 +2.6059612365309683e+00 +2.0638030661393503e-01 +-2.8111541090501424e+00 +1.6752599770887562e+00 +1.9472935207057326e-01 +-2.1479915819733422e+00 +-7.8353045417117650e-01 +2.0669596850741093e-01 +-2.6724807090487159e+00 +1.6066745025625850e+00 +2.0018532746219386e-01 +-2.2015647937379814e+00 +1.7101530457706819e+00 +2.0169965419672248e-01 +-2.1391049877358839e+00 +-8.8829467353551339e-01 +2.0819362998634777e-01 +-2.5016851976892336e+00 +1.3979700220907951e+00 +1.7122929434635564e-01 +-1.0014885999172023e+00 +2.4481694754271039e+00 +2.4485344446628751e-01 +-2.4287644750725130e+00 +-4.4415693272322976e-01 +2.9071117048479933e-01 +-4.1505538434785718e+00 +3.0085743533826657e+00 +2.7791303622749342e-01 +-3.2073625249605211e+00 +3.0293870126734173e+00 +2.7803147621804208e-01 +-3.1618976684357554e+00 +7.2851408755921543e-01 +3.0106419291387315e-01 +-2.9595384405843213e+00 +2.9635713981656462e+00 +3.4871617038329228e-01 +-3.2219263068757740e+00 +1.4141257202665327e+00 +2.3342743060591761e-01 +-1.1328283848942722e+00 +1.4817894050584286e+00 +2.0422996334304780e-01 +-5.2074473452985026e-01 +2.9774134860736732e+00 +3.5862001363649770e-01 +-3.2403798378768225e+00 +1.3555872690071167e+00 +2.3977976472481188e-01 +-1.1182066060617197e+00 +3.0501780469982229e+00 +3.6234040900039804e-01 +-3.2282426068214587e+00 +1.3610394297833022e+00 +2.5081589837718521e-01 +-1.2422060950701526e+00 +1.8915646666736885e+00 +4.4193834188871650e-01 +-4.6955410174664589e+00 +1.3877101546224890e+00 +2.4843276349770130e-01 +-1.0250484630111243e+00 +1.3699300701211752e+00 +2.5577340437987417e-01 +-1.1587166189572482e+00 +3.0309098446909464e+00 +4.0044241964517530e-01 +-3.2061991929053422e+00 +1.4121090158985705e+00 +2.5440203033606423e-01 +-9.5049078497065520e-01 +1.4534061691116014e+00 +2.5519662073004823e-01 +-9.6638290486157052e-01 +1.4123755425816309e+00 +2.5463298827788383e-01 +-9.3595658431642914e-01 +1.9291981800125857e+00 +3.7391400165082955e-01 +-2.8976924717819421e+00 +3.0059922883279189e+00 +4.1686921860288839e-01 +-3.2041443444411666e+00 +1.3621926953657884e+00 +2.9390838231542732e-01 +-1.2440696245229446e+00 +5.8266539026649988e-01 +3.7596108782892856e-01 +-2.7165813255475393e+00 +1.3725063772106336e+00 +2.8769409523764222e-01 +-1.0826372874019528e+00 +1.3763503009045832e+00 +2.9720174865662419e-01 +-1.1695649049634638e+00 +3.0223373154704736e+00 +4.7480327998111693e-01 +-3.2474455264553161e+00 +6.3561870960396716e-01 +4.0132508244017978e-01 +-2.8636795176307541e+00 +1.3532484062949703e+00 +3.0668626984605818e-01 +-1.2039548454989335e+00 +3.0894130983996193e-01 +3.8486873648592146e-01 +-2.5622403614549616e+00 +2.0003123146991197e+00 +4.5524069654454691e-01 +-2.9287927580607738e+00 +5.1535517911387152e-01 +4.1041650639686855e-01 +-2.8000994294441570e+00 +4.0219138680508781e-01 +3.9443799734876067e-01 +-2.5718419178796279e+00 +1.3844855637525628e+00 +3.3298658863879999e-01 +-1.2621915080992849e+00 +1.3594488981254023e+00 +3.3362150348408476e-01 +-1.2033607316204762e+00 +2.0003470088815694e+00 +4.7622607145586254e-01 +-2.8536233461518661e+00 +1.2683517392024242e+00 +3.2812958305763584e-01 +-1.0878242553504591e+00 +1.4182989442136109e+00 +3.5166903576252395e-01 +-1.3003707870430790e+00 +1.4561189739721265e+00 +3.5785480191558766e-01 +-1.3623468858854413e+00 +1.3667124439944893e+00 +3.4306720567043580e-01 +-1.1398086513188321e+00 +1.3933637171163060e+00 +3.3732170818352636e-01 +-1.0316957283450423e+00 +1.3768445772527502e+00 +3.4433365103205515e-01 +-1.0888253379557833e+00 +1.4159647694626198e+00 +3.6018424545959377e-01 +-1.3101983318037147e+00 +1.3918940118947269e+00 +3.4294978712621355e-01 +-1.0358516205253565e+00 +2.0711064997647924e-01 +4.3965700118870799e-01 +-2.7223721232101661e+00 +1.4384439162453200e+00 +3.4455206032546015e-01 +-1.0324914776257716e+00 +1.3618934896547126e+00 +3.6031596669504951e-01 +-1.2140951264172561e+00 +1.3994769612888815e+00 +3.4582757070860659e-01 +-1.0077632846373183e+00 +1.4142422919881164e+00 +3.7243222992488917e-01 +-1.3096278321046066e+00 +-2.6326204185356822e-01 +5.1346162142121876e-01 +-3.7598308779132004e+00 +1.3845282701698594e+00 +3.6154801074845977e-01 +-1.0767927582177343e+00 +1.3780348206733604e+00 +3.7876939127878445e-01 +-1.2867434452865187e+00 +-8.9770415105782730e-01 +4.3153419151322131e-01 +-2.5410976296198577e+00 +-1.0834470030404943e-01 +3.1438306568388752e-01 +-7.6264540231288280e-01 +3.8226994096423311e-01 +5.7185493783762464e-01 +-3.2255074115672944e+00 +1.4074707671155149e+00 +4.3204018843138076e-01 +-1.2571044735989143e+00 +-9.1507323460182310e-02 +3.2679418084876394e-01 +-7.7486651398124140e-01 +-9.7338602778983319e-02 +3.2695822487735932e-01 +-7.2859816013768253e-01 +-9.0491930702691750e-02 +3.2817494031100169e-01 +-7.3762297514486819e-01 +1.5760529737671429e+00 +4.1321482058329323e-01 +-6.4809967171305172e-01 +-1.0171083987911707e+00 +6.9903445241324058e-01 +-2.2534023152200282e+00 +-1.0003456872594081e+00 +7.3983272041349590e-01 +-2.5399286242975401e+00 +-1.2107793071945656e+00 +7.3130726595298279e-01 +-2.3940864877870891e+00 +-1.1291851497477698e+00 +3.0838948900420549e-01 +-1.3125727288975081e-01 +-1.0354981232532956e+00 +8.2848159715020087e-01 +-2.7285864101697999e+00 +-3.0430532025335091e-02 +1.1065061660663904e+00 +-6.8100318299706919e-01 +-6.4050638761307330e-02 +1.2101725909401346e+00 +-7.5999670423108590e-01 +-6.3581570454295785e-02 +1.2230621141386324e+00 +-7.7576445170026154e-01 +-7.3864628000516880e-02 +1.2345523926705495e+00 +-7.7477936786364254e-01 +-4.4418521343078866e-02 +1.2574978311288858e+00 +-7.5195371933818544e-01 +-4.9480241323239631e-02 +1.2877176973284405e+00 +-7.4785755504760232e-01 +-5.3296743716894401e-01 +-2.6600389701627269e-02 +-4.9818545668124997e-01 +-5.3179260863965494e-01 +-2.3612144777168925e-02 +-5.0054770985752672e-01 +-3.8121096984693420e-01 +-4.2833955477757889e-02 +-7.6253575596029533e-01 +-3.2392432137313293e-01 +-4.0920419729194010e-02 +-7.4588660188113354e-01 +-3.7713717322732870e-01 +-7.6670753242541129e-03 +-7.5505410891798963e-01 +-3.6532712307674109e-01 +1.1368442513756301e-02 +-7.5059484638319784e-01 +7.5759115278725242e-01 +-1.1646811052922423e-01 +-3.1654857954247100e+00 +7.2295068440431698e-01 +-1.1445301284523800e-01 +-3.1646475485436283e+00 +7.9883590655856540e-01 +-8.0470857236468948e-02 +-3.1473426081156139e+00 +7.6745739054228845e-01 +-6.8114366454841743e-02 +-3.1156730403050705e+00 +5.3988746041626823e-01 +-1.9180059433229497e-02 +-2.6760090916639507e+00 +7.3480328403694750e-01 +-2.6470365440065251e-02 +-3.0882027071828735e+00 +6.2234858665491688e-01 +-1.6584684710853847e-02 +-2.8580896322883449e+00 +1.5447391101222407e+00 +-3.1697144105242525e-04 +-2.1676959813888708e+00 +1.0758474326821894e+00 +1.3951244664841001e-02 +-3.3606598524607820e+00 +-7.9432005051413934e-01 +6.2414354160395959e-02 +-2.6677455116635058e+00 +-8.5220564988993297e-01 +6.5460999121400770e-02 +-2.4771658412574853e+00 +1.0919524370450433e+00 +2.9029415392624124e-02 +-3.3912197853711965e+00 +2.4937417810368459e+00 +-3.5422411669546131e-03 +-2.3098109037438657e+00 +1.3830872538191727e+00 +3.7622074195063006e-02 +-1.1459618081715444e+00 +1.4242036676613168e+00 +3.9591458797266645e-02 +-8.3221581831711156e-01 +-8.1775392340649478e-01 +7.9162007037925142e-02 +-2.4347352427798281e+00 +1.5435205048740872e+00 +3.7606714670251049e-02 +-7.6876256750609862e-01 +2.4923944087150378e+00 +1.5085925247204580e-02 +-2.3951191200131965e+00 +1.4513193320409172e+00 +4.5847160892293078e-02 +-3.8514234233105182e+00 +-8.7372770030871239e-01 +8.7797143824555141e-02 +-2.5800622792566084e+00 +1.3587247940373810e+00 +5.5066117652444707e-02 +-1.1960205240415571e+00 +1.3703704125500284e+00 +5.8593065333687890e-02 +-1.2492268753704425e+00 +6.8792998264963334e-01 +7.5421649685808362e-02 +-3.0421775229815853e+00 +1.3806491303893482e+00 +5.9030159264902127e-02 +-1.1991503042310534e+00 +6.1514597986251074e-01 +8.4069066857434607e-02 +-3.0048603855214573e+00 +1.5786080942573815e+00 +6.5456042995272232e-02 +-2.2464807548288910e+00 +1.6310423790525492e+00 +6.8600096838629512e-02 +-2.1900074731665846e+00 +1.6843410143404762e+00 +6.7704632843375481e-02 +-2.1180465784647060e+00 +1.4612381584546126e+00 +9.5550617071810409e-02 +-2.2414894843776572e+00 +6.9022158018605373e-01 +1.2283854056905413e-01 +-2.8313238232831512e+00 +8.1887242563562335e-01 +1.2708601128255584e-01 +-3.0997200876559465e+00 +1.3968922902758314e+00 +9.3592648052451502e-02 +-1.0102686540733556e+00 +1.7137448182376867e+00 +1.2856708542135989e-01 +-4.1822959094266841e+00 +1.6949788534361527e+00 +1.2966967272558561e-01 +-4.1509961695025135e+00 +-8.2395592293168352e-01 +1.4853553525454755e-01 +-2.3837039286559092e+00 +-8.1733753740055681e-01 +1.5310662542585415e-01 +-2.4213143967009660e+00 +1.6766199602737220e+00 +1.6571024726385200e-01 +-4.1758611603023006e+00 +2.5463954516006306e+00 +1.1931860597072876e-01 +-2.2560053827766113e+00 +2.6816663909807956e+00 +1.3983919646302692e-01 +-2.7804628264769100e+00 +2.6842569783408843e+00 +1.5490379499229626e-01 +-2.7742434662539370e+00 +6.5881779091503201e-01 +1.7991982234975376e-01 +-2.9529831165648810e+00 +8.0469724797341557e-01 +1.8544403242794505e-01 +-3.0441143475500150e+00 +1.0054035653242328e+00 +1.9051067595767890e-01 +-3.2683209404916216e+00 +2.9121575515872387e+00 +1.7108175286749652e-01 +-3.1023081833426525e+00 +5.1603553709410777e-01 +1.9271740848653279e-01 +-2.9685932275480580e+00 +2.9699590398557731e+00 +1.8698888392873811e-01 +-3.1647127876837922e+00 +2.9699590398557731e+00 +1.8698888392873811e-01 +-3.1647127876837922e+00 +2.0231050362510636e+00 +1.7584815837659376e-01 +-2.3415185465754598e+00 +2.9900700249416614e+00 +2.0209253883611242e-01 +-3.1831930070484438e+00 +-7.9460835599885271e-01 +2.0128979406596909e-01 +-2.5815440206428582e+00 +1.5777430091362918e+00 +1.3964324779136308e-01 +-5.5415703464646471e-01 +1.6885966953733613e+00 +1.8991741151853828e-01 +-2.1278503223463359e+00 +2.9934800327498965e+00 +2.1799610063973926e-01 +-3.1854716657038398e+00 +2.9934800327498965e+00 +2.1799610063973926e-01 +-3.1854716657038398e+00 +1.3996568319017346e+00 +1.6306689326716498e-01 +-9.9647606267834166e-01 +-8.5971751115666151e-01 +2.0392026686608386e-01 +-2.5186027271528912e+00 +2.5382079716606114e+00 +2.0302579495405376e-01 +-2.2829196126273419e+00 +2.5069131395473363e+00 +2.0869345406166828e-01 +-2.3321645163004701e+00 +7.5504666513169050e-01 +2.5896896115374718e-01 +-2.8945799985867815e+00 +2.9703398838710187e+00 +2.7986290799304631e-01 +-3.2327985599906799e+00 +1.5540126166448336e+00 +2.4370180455260965e-01 +-2.2571861741181309e+00 +6.5546720341394282e-01 +2.6592162910236966e-01 +-2.9048286634439728e+00 +6.6618321233713618e-01 +2.9775035735999406e-01 +-2.8052504288985172e+00 +1.0157955329863340e+00 +3.2652874056902753e-01 +-3.2388925019108865e+00 +1.3564257855674264e+00 +2.2957527462576419e-01 +-1.1131817409869535e+00 +2.9735970230061759e+00 +3.4120906146071001e-01 +-3.2268398681900465e+00 +1.3972327022026825e+00 +2.3886446200537334e-01 +-1.2988014732563438e+00 +1.3686393533787482e+00 +2.3300465593400088e-01 +-1.0867399091500007e+00 +-7.7321255520403176e-01 +2.7789982643363215e-01 +-2.6290714254399767e+00 +1.3759310108854965e+00 +2.3338235898097179e-01 +-1.0638081308137708e+00 +1.3788706731151585e+00 +2.3355809110943021e-01 +-1.0421195203238864e+00 +1.3867726292099483e+00 +2.3461506788847170e-01 +-1.0221579338918636e+00 +1.3337692649847650e+00 +2.4017113240771498e-01 +-1.1654280457746982e+00 +1.3910443104834778e+00 +2.3413143485035026e-01 +-9.9791871871013871e-01 +1.4337778240552519e+00 +2.3571043881925055e-01 +-1.0127347419089126e+00 +1.5582171729067982e+00 +2.2584202761181366e-01 +-6.5766426102658559e-01 +2.0808089420298668e+00 +3.3269974727922869e-01 +-2.4777161377144830e+00 +2.0808089420298668e+00 +3.3269974727922869e-01 +-2.4777161377144830e+00 +1.5495219298720804e+00 +2.2929285772815391e-01 +-6.2577947627340924e-01 +1.5611596858392043e+00 +2.3012462136714382e-01 +-5.4515218857475678e-01 +3.0314625081746751e+00 +4.0059559058347571e-01 +-3.1880109288722926e+00 +3.0004674783301946e+00 +4.0885537593218846e-01 +-3.2055116030713249e+00 +-8.5235550213638767e-01 +2.9652251488663722e-01 +-2.4121719454673927e+00 +5.1989342865833710e-01 +4.0620857764127949e-01 +-2.8225802251123380e+00 +6.1923906015245089e-01 +4.2532998380892217e-01 +-2.8395137543294644e+00 +5.1877764817414440e-01 +4.1112393980052531e-01 +-2.6567623778890974e+00 +1.3811428466417677e+00 +3.3301121784734566e-01 +-1.2543718549237211e+00 +-1.4455460482914437e-01 +2.6196347878775833e-01 +-7.2001574415427927e-01 +1.4490619142393315e+00 +3.3934901239861326e-01 +-1.2404843219829689e+00 +1.3399262857932606e+00 +3.3281817691459176e-01 +-1.1516835732002679e+00 +1.4317129764221956e+00 +3.3771597172365447e-01 +-1.2172019617055401e+00 +1.3818264249255594e+00 +3.3937081450533318e-01 +-1.2103922385203387e+00 +1.3613143679990978e+00 +3.3882914876585846e-01 +-1.2003647108045477e+00 +1.4218884215593808e+00 +3.4235357617031997e-01 +-1.2316658583764561e+00 +1.3497499473760426e+00 +3.3851474617407074e-01 +-1.1691292562229303e+00 +1.3749027099945634e+00 +3.4054813519404464e-01 +-1.1746564465873459e+00 +1.3749027099945634e+00 +3.4054813519404464e-01 +-1.1746564465873459e+00 +1.4161146707107446e+00 +3.3422127632322379e-01 +-1.0947126972658725e+00 +1.9978183834222072e+00 +4.8791813291953967e-01 +-2.8741590332038101e+00 +1.3633329233456415e+00 +3.4049520949355838e-01 +-1.1600800686338213e+00 +1.3853112980761335e+00 +3.3368550435772815e-01 +-1.0318907382917315e+00 +1.3659289912995980e+00 +3.4249343722654463e-01 +-1.1485862226109504e+00 +1.3154808902455404e+00 +3.3844142380190517e-01 +-1.1217061308694936e+00 +1.3871244371789999e+00 +3.4338680460169052e-01 +-1.1752399701276250e+00 +1.4095031379303178e+00 +3.3361135556597848e-01 +-1.0127786386116189e+00 +1.3775482815400732e+00 +3.4184387873862088e-01 +-1.0841933686775838e+00 +1.3801884152703370e+00 +3.4177402081989178e-01 +-1.0761362922366358e+00 +1.4101957639701217e+00 +3.4281157900535308e-01 +-1.1000544622444495e+00 +1.3282329297040318e+00 +3.3073389816437548e-01 +-9.2011152500145532e-01 +1.2612547786003232e+00 +3.3660099835246238e-01 +-9.8481887287107750e-01 +1.4164259872115947e+00 +3.4504177239000750e-01 +-1.0992994392448654e+00 +1.4174550366765333e+00 +3.4550008711843083e-01 +-1.0807140124149075e+00 +3.0582383742365737e-01 +4.4455016842103406e-01 +-2.5642147375876769e+00 +-8.5479155964808340e-01 +3.9616037060775083e-01 +-2.3631208732072921e+00 +-6.2332468212443100e-02 +5.3292767362994231e-01 +-3.5036994706959752e+00 +2.4753816621845762e-01 +5.2945356854096826e-01 +-3.2222286582428916e+00 +-1.0380040139525290e-01 +3.0123048610504488e-01 +-7.3205404582104938e-01 +-9.8264762506120262e-02 +3.0766741510893847e-01 +-7.3556957132300349e-01 +1.4543241549040757e+00 +3.9160464695441383e-01 +-1.0302796367552554e+00 +3.1647208032035956e-01 +5.5823010624525460e-01 +-3.2347336666431739e+00 +1.3948216592137868e+00 +4.2284780412030665e-01 +-1.2245442111370690e+00 +-8.8982798920005796e-02 +3.1387770995314374e-01 +-6.9085017680311278e-01 +1.4948440974257939e+00 +4.2930990481092379e-01 +-1.1684837782351012e+00 +1.5767986454124090e+00 +4.0177230471363506e-01 +-6.1316024447390161e-01 +-9.0488653819138565e-02 +6.5518662888075485e-01 +-3.7588592309199838e+00 +1.5760805858058518e+00 +4.1313902021394050e-01 +-6.3457785154331403e-01 +1.5740089623430069e+00 +4.1658313869827091e-01 +-6.3279858670455535e-01 +1.5157257834623989e+00 +4.7122651673095362e-01 +-9.2751935684002929e-01 +1.5872823127808819e+00 +4.8933033925013458e-01 +-7.1590184960712944e-01 +1.5564282036834576e+00 +4.8966536031646452e-01 +-6.5396724048262200e-01 +-1.0023062373203553e+00 +5.9541033205429750e-01 +-2.3977105316555893e+00 +-7.9642072326240299e-01 +6.6677914109131531e-01 +-2.6490937940130328e+00 +-9.6225180538943855e-01 +6.2216137540516114e-01 +-2.2771428676729686e+00 +-9.9943958585794457e-01 +6.1963690969169294e-01 +-2.2439626242600448e+00 +-1.0329707977986231e+00 +6.2188792445084773e-01 +-2.2253140958576600e+00 +-1.0696193951206963e+00 +6.3571999930596967e-01 +-2.3345560721069805e+00 +-8.9266457880192285e-01 +7.2029261850642978e-01 +-2.3408935116865437e+00 +-8.9266457880192285e-01 +7.2029261850642978e-01 +-2.3408935116865437e+00 +-1.0227249214803533e+00 +7.2075479678025400e-01 +-2.2739575252758262e+00 +-5.9402082956852661e-02 +1.0950598036055530e+00 +-8.4872391022693305e-01 +-6.3972379696961998e-02 +1.1918006288472003e+00 +-7.6600887841056742e-01 +-7.5548666649069340e-02 +1.2317203848101250e+00 +-7.7930022206416316e-01 +-3.2612082753286464e-01 +-4.2226722501239815e-02 +-7.4606461421718639e-01 +-3.7148775280966856e-01 +-2.9015697594551876e-02 +-7.5570047459004863e-01 +-3.8096880557283536e-01 +-8.4442286406014623e-03 +-7.5591611911319234e-01 +-3.7739172107023689e-01 +-7.6978581171478462e-03 +-7.6446732584657751e-01 +-3.7975140298955640e-01 +-5.2425887829484529e-03 +-7.5866513665131952e-01 +-3.8430627035054965e-01 +-3.4239703067611925e-03 +-7.5794709759606116e-01 +-3.7537929701595801e-01 +6.5720635798908718e-04 +-7.5861133940944347e-01 +-3.7720189418319144e-01 +1.6205925560436457e-03 +-7.5929955900392332e-01 +-3.7466513082892955e-01 +2.1636371745461266e-03 +-7.5651148770591548e-01 +-3.7862361100658604e-01 +2.5117943464251856e-02 +-7.5296545977620755e-01 +7.8866848729740391e-01 +-1.0286662320000386e-01 +-3.1472113028141164e+00 +-6.5453653416866417e-02 +2.4925039779478176e-02 +-1.1846809428633229e+00 +7.8122515714627971e-01 +-6.4276893577468935e-02 +-3.1342119354247129e+00 +7.9249227172475911e-01 +-6.0465217509433324e-02 +-3.1198411512476727e+00 +7.9249227172475911e-01 +-6.0465217509433324e-02 +-3.1198411512476727e+00 +1.3532851371055108e+00 +-1.7599545594266214e-02 +-1.1042180485456832e+00 +3.1647049393191801e-01 +3.5183857227812747e-02 +-8.0115729534670088e-01 +3.2530154999498806e-01 +3.6789278844720517e-02 +-8.0155778939768574e-01 +1.5278800419872964e+00 +-3.0496744807107144e-02 +-2.1250803871153843e+00 +1.7071795232084670e+00 +-3.6221724950615007e-02 +-2.1380235285469666e+00 +1.4467053057391759e+00 +-2.5793220763658583e-02 +-2.2265666196997751e+00 +1.7042978981317058e+00 +-1.9743816925866978e-02 +-2.1356946463799202e+00 +2.0575316324965147e+00 +-3.3578769478006247e-02 +-2.3335804901361716e+00 +2.0064796287941142e+00 +-1.6699676894080858e-02 +-2.3276050049150685e+00 +2.0064796287941142e+00 +-1.6699676894080858e-02 +-2.3276050049150685e+00 +6.1220350890860964e-01 +3.3994985285950359e-02 +-3.0566820899141676e+00 +1.2823315976350440e+00 +1.7556044291272062e-02 +-3.6199353612374594e+00 +1.3992443883135308e+00 +3.6081200486090488e-02 +-1.1066222300379269e+00 +9.2468587315997142e-01 +6.1636638798502910e-02 +-3.1926817921708679e+00 +1.3815866215628232e+00 +5.3359687419266881e-02 +-1.2737483508560432e+00 +1.3598282355520364e+00 +5.9502819132721201e-02 +-1.1512249874578668e+00 +1.3950919798799426e+00 +6.8926305581079372e-02 +-2.2818479948672845e+00 +1.8272642675525075e+00 +5.1161395889670121e-02 +-1.2430984246316166e+00 +2.7097748929060601e+00 +4.5998271134021738e-02 +-2.8220843024576152e+00 +1.4454375361145009e+00 +7.7685766141450424e-02 +-2.2341266065069640e+00 +1.6863070296131177e+00 +7.3025003366951113e-02 +-2.1269653186971813e+00 +1.1487507880563101e+00 +9.0047970560435481e-02 +-3.4543856837827804e+00 +6.9961013636517499e-01 +1.0629261029021143e-01 +-2.9882753977122940e+00 +6.8624082730187930e-01 +1.0776860475150031e-01 +-2.9941626051362333e+00 +1.3957360988813698e+00 +9.0269133512018304e-02 +-1.0114972138620866e+00 +1.3849192258404757e+00 +1.0114904953120592e-01 +-1.0060442708204811e+00 +1.9859071724307336e+00 +1.1324184308925171e-01 +-2.3434208931756513e+00 +1.6267444652068228e+00 +1.2669537384751128e-01 +-2.2130812538353650e+00 +5.2959011698472336e-01 +1.5144418555575503e-01 +-2.9904500898011297e+00 +2.0429364124881904e+00 +1.3236873918782846e-01 +-2.3998631928240148e+00 +7.3227767528544752e-01 +1.6381828646716892e-01 +-2.9942126246933105e+00 +-8.5666317851956386e-01 +1.9197184932671876e-01 +-2.4080828601947686e+00 +1.3676531496625399e+00 +1.6991504497634291e-01 +-1.1937533879496944e+00 +1.5949910927282709e+00 +2.0528473477569531e-01 +-2.2339541176116624e+00 +1.6071393701626373e+00 +2.0475093269031880e-01 +-2.1744134291657358e+00 +1.5787006333463327e+00 +2.0454369048350915e-01 +-2.1682340605087371e+00 +1.5818771774971789e+00 +2.0909531489846164e-01 +-2.2071859518600658e+00 +1.5976719206475958e+00 +2.0922795205420688e-01 +-2.2144196851014022e+00 +1.5976719206475958e+00 +2.0922795205420688e-01 +-2.2144196851014022e+00 +7.4536613811334040e-01 +2.3546546568018845e-01 +-3.0014864648663413e+00 +2.4649165679306719e+00 +2.2758117080961465e-01 +-2.3563164672237611e+00 +1.6380220586505401e+00 +2.2999051013051661e-01 +-2.1815077250108423e+00 +6.7058990755343950e-01 +2.5427966632375337e-01 +-2.9201576570483878e+00 +6.2158279283213647e-01 +2.6676140039713758e-01 +-2.8871187094512503e+00 +6.2542395294225206e-01 +2.7388997948111327e-01 +-2.8823100147430285e+00 +1.3639869525294632e+00 +2.5720757650623305e-01 +-2.2906178813805589e+00 +1.3438577737176258e+00 +2.1204998322357985e-01 +-1.0855156511061907e+00 +1.3614804588102967e+00 +2.1370105921490623e-01 +-1.0957528274484782e+00 +1.3512776117880747e+00 +2.7176018894515741e-01 +-2.2784027555985307e+00 +1.4776360336629728e+00 +2.7561829305770469e-01 +-2.2405200043578728e+00 +6.7440555175144301e-01 +2.9886966902454226e-01 +-2.8977883796932908e+00 +-3.0461814476359017e-01 +3.2084855763722625e-01 +-3.7856365872472861e+00 +2.9603697874445252e+00 +3.3257811889470762e-01 +-3.2222123954814181e+00 +6.3136979397415738e-01 +3.0113463170613314e-01 +-2.8689460622568501e+00 +1.4366189592805787e+00 +2.8249646772315140e-01 +-2.2182311340777261e+00 +1.3604210516470376e+00 +2.3214279246134406e-01 +-1.1113540431453364e+00 +1.3884193335488539e+00 +2.3326915061333864e-01 +-1.1232273249155973e+00 +1.4073321659810643e+00 +2.3278383309852216e-01 +-1.1364311808050902e+00 +1.3643322759303826e+00 +2.3271195419028276e-01 +-1.0956968478723912e+00 +1.3819256996496814e+00 +2.3392479394838939e-01 +-1.0337603698476185e+00 +1.3882303289988818e+00 +2.3451205964410810e-01 +-1.0038143419808088e+00 +1.3918974680171667e+00 +2.3407327334022779e-01 +-9.8983259990451600e-01 +6.2873199102519595e-01 +3.2263212431755889e-01 +-2.8663891112410460e+00 +1.4628178825940410e+00 +3.0743893541321954e-01 +-2.2828359306677140e+00 +6.3228326191112738e-01 +3.2582160739047278e-01 +-2.8662451607774342e+00 +1.5623703318800162e+00 +2.2920416119985842e-01 +-6.5875965550382720e-01 +1.0855858051633251e+00 +4.0855392248599148e-01 +-3.4765890659772327e+00 +6.2531274228986589e-01 +3.7312482799140256e-01 +-2.8604221076232812e+00 +5.4916931131576263e-01 +4.0470190349637053e-01 +-2.8220865964710713e+00 +1.3411963779084584e+00 +3.1095554288507388e-01 +-1.1254310524988878e+00 +4.0164524532343060e-01 +4.1064401711775467e-01 +-2.8618428461365011e+00 +2.0564057325633169e+00 +4.6404758711245414e-01 +-2.9312805003662681e+00 +2.0208884241071905e+00 +4.6030010609290617e-01 +-2.8523976709638896e+00 +4.6424178835828500e-01 +4.1335419477874680e-01 +-2.7093463170372503e+00 +1.4035167815359844e+00 +3.3101662054538605e-01 +-1.2356950894979910e+00 +1.3835823980896331e+00 +3.3798075747497991e-01 +-1.2529151316923031e+00 +1.3660721048303137e+00 +3.3169518421130362e-01 +-1.1442676573696249e+00 +1.3660721048303137e+00 +3.3169518421130362e-01 +-1.1442676573696249e+00 +1.3564902845420475e+00 +3.3049268137080262e-01 +-1.0793437087111040e+00 +1.4025217976900599e+00 +3.4306889147815339e-01 +-1.2375784064514206e+00 +1.4162538890028480e+00 +3.4528174566156461e-01 +-1.2131136594875949e+00 +1.4566213019409495e+00 +3.4808049454422851e-01 +-1.2428272855690798e+00 +1.9751609162771753e+00 +5.1009081835078796e-01 +-2.8915941638038620e+00 +1.9751609162771753e+00 +5.1009081835078796e-01 +-2.8915941638038620e+00 +2.3189705093616038e+00 +5.4655237215126062e-01 +-3.3420650233380562e+00 +4.2559378817364035e-01 +4.4246008168633505e-01 +-2.6053169667762988e+00 +-7.5635403413403779e-01 +4.0980237613586196e-01 +-2.6563811692251420e+00 +9.2929141163013518e-01 +3.1556919966185126e-01 +-6.7881559675214009e-01 +1.4096359969617880e+00 +3.7759047113048499e-01 +-1.3070946186924810e+00 +1.4337023031639613e+00 +3.6423858895341271e-01 +-1.0870603303266360e+00 +-8.8330169942422476e-01 +4.3681940706340111e-01 +-2.5701196088068556e+00 +1.4777191356038659e+00 +3.8896239444839426e-01 +-9.1100364578866566e-01 +1.3882131504576092e+00 +4.1947101655219615e-01 +-1.1922102321979291e+00 +2.5504212100153800e-01 +6.0380920904487667e-01 +-3.2152132042959622e+00 +2.3158573444495906e-01 +6.0915961201439728e-01 +-3.2072174539480947e+00 +-1.0996049312675378e+00 +5.4670218984931296e-01 +-2.3358352736596002e+00 +1.5859548676750557e+00 +4.9248315135858584e-01 +-5.2021263388621342e-01 +-9.9734788112225103e-01 +6.0979588301215537e-01 +-2.4278819523794928e+00 +-9.1752399518490435e-01 +6.1717672233027276e-01 +-2.3741116314826880e+00 +-9.8077233051107560e-01 +7.3172599867687771e-01 +-2.5234353090565271e+00 +-6.4016820731781110e-02 +1.2332755077752238e+00 +-7.8822967582567460e-01 +-6.3034267767125951e-02 +1.2355417197067184e+00 +-7.8289432425321082e-01 +-8.8563211733614267e-01 +-2.1785637200870688e-02 +-3.0835309919131187e-01 +7.9608843610222413e-01 +6.8535298339941764e-02 +-2.9854679418527108e+00 +2.3211451391989821e-01 +5.2554364095447481e-01 +-4.4710395542055412e+00 +-1.5102314391675314e-01 +2.5998932401417663e-01 +-3.4263235070996059e+00 +-1.3524793835749127e-01 +3.8016174123382718e-01 +-3.3872428620615525e+00 +3.1265799086298152e-01 +4.0485508894071814e-01 +-3.1137427939556002e+00 +-6.6745498626516664e-01 +4.3482502937865686e-01 +-3.4797380044972854e+00 +-3.3810046733785307e-04 +4.7551361594382874e-01 +-4.2919654038419059e+00 +-7.4738625555755622e-01 +6.2527462080126150e-01 +-2.7839839988552555e+00 +-7.4738625555755622e-01 +6.2527462080126150e-01 +-2.7839839988552555e+00 +8.0797879128568251e-01 +1.3890030196841993e-01 +-2.9641621163172500e+00 +-2.8716406656679472e-01 +3.2347079207910656e-01 +-3.7411043700393893e+00 +-2.0326586735914540e-01 +3.4200758720997088e-01 +-3.5326658138428573e+00 +3.6532129658522411e-01 +4.1377110113525889e-01 +-2.8298623071154250e+00 +2.2005202035535745e-01 +6.4764932061712499e-01 +-4.5259067921333962e+00 +8.1289965868100422e-01 +1.5753843845235582e-01 +-2.9851814889979797e+00 +1.2729350429478381e+00 +2.3970706409404446e-01 +-3.5581071232313426e+00 +-2.5547309338351454e-01 +3.7301237868363657e-01 +-3.7024701961408653e+00 +-8.3166050448054729e-01 +5.5636257476716455e-01 +-2.6100161276815368e+00 +5.0036599555373451e-01 +-6.9340377316604029e-02 +-2.7917329248545948e+00 +4.1341682735578877e-01 +-5.1232023953944862e-02 +-2.8350817924165765e+00 +2.3426226748013532e-01 +-6.8825733079503357e-03 +-2.7682021573752116e+00 +9.9005577019889268e-02 +1.8069120222540275e-03 +-2.7800718163105467e+00 +4.2973556692698073e-01 +6.4285556242713704e-02 +-2.8392377134229121e+00 +4.5496223180836415e-01 +1.6766301717614268e-01 +-2.7112397399663957e+00 +1.0888480152292475e+00 +1.5943092819399435e-01 +-3.2934635356607753e+00 +2.1454146438967481e-01 +2.4480566265881959e-01 +-4.3052165086745227e+00 +7.5949312292393845e-01 +2.4814126721298013e-01 +-2.9169712948478623e+00 +2.5536357131411197e-01 +3.3011502618300181e-01 +-4.0356356270907732e+00 +6.1751434592516918e-01 +3.4839790700651740e-01 +-2.8135032272352052e+00 +-2.4675162583309171e-01 +3.8452384386435623e-01 +-3.6783862063794164e+00 +3.8312237284556311e-01 +4.0483623722825157e-01 +-2.9316250753757096e+00 +2.2172271623518039e-01 +4.7786039592126389e-01 +-3.4620990851260354e+00 +2.1821108713547790e-01 +5.6658087752984421e-01 +-4.6151051891976289e+00 +8.6201421273416665e-02 +5.0966259809296632e-01 +-3.0380411804548770e+00 +7.3114500678751193e-02 +5.1308929133928760e-01 +-3.0696993829314434e+00 +-5.9289550575630023e-01 +-5.1108526596428547e-02 +-3.6608087717729663e+00 +4.9105909308515455e-01 +-3.6046399345370260e-02 +-2.7994724452113346e+00 +4.9105909308515455e-01 +-3.6046399345370260e-02 +-2.7994724452113346e+00 +1.0119262395374520e+00 +1.1955058760591128e-02 +-3.2143521025455501e+00 +5.6118580193565082e-01 +6.4390019378662289e-02 +-2.7692571851834855e+00 +1.9573476764555180e+00 +4.3985483892653165e-02 +-3.4817027354353693e+00 +-2.1514640816063021e-01 +3.0499180345486321e-01 +-3.5875762113236846e+00 +-1.8051768811724822e-01 +3.2560455073044903e-01 +-3.5050967412666854e+00 +-7.1866095694707449e-02 +3.2552898430474675e-01 +-3.2893469931452195e+00 +5.0668608066529552e-01 +3.3781043202485234e-01 +-2.7004040626251777e+00 +-2.4918036501340607e-01 +4.7326559580583144e-01 +-3.6995681962313594e+00 +-5.4965911322166017e-01 +4.7550986808714274e-01 +-3.5295413552394819e+00 +-3.2003139982706102e-01 +5.0963923526046107e-01 +-3.7233002787512000e+00 +3.9111420148444559e-01 +5.5705982253113728e-01 +-3.2663162074391217e+00 +-2.7636019013262142e-01 +5.6751821960256688e-01 +-3.7269601624089921e+00 +3.2708455488326238e-01 +6.4286361548766335e-01 +-3.7093383791228467e+00 +7.7008102746737561e-01 +-4.4421735718932383e-02 +-2.9391290901656668e+00 +7.7866902551225048e-01 +-4.5569756265409614e-02 +-2.9533624266849126e+00 +-9.0090564785261606e-01 +5.6348507458801884e-02 +-2.4835892347001916e+00 +8.1362110553688000e-02 +6.4675608966838095e-03 +-2.8869724437195656e+00 +1.1096844022016599e+00 +-4.2987214236493536e-02 +-3.3355706447625177e+00 +-9.0286716506840636e-01 +9.4423757745291756e-02 +-2.5311842064613925e+00 +7.9426653102143296e-01 +4.7810620239538186e-02 +-2.9775276540970301e+00 +7.9426653102143296e-01 +4.7810620239538186e-02 +-2.9775276540970301e+00 +4.8492078998672322e-01 +1.0928537937510820e-01 +-2.7930117799624723e+00 +7.6372531299015789e-01 +1.0834201119569760e-01 +-2.9406484005497084e+00 +6.7376063208693215e-01 +2.4511110988385823e-01 +-2.8707063193529736e+00 +-5.2554974020764267e-01 +2.8611753682997049e-01 +-3.6042219438156216e+00 +6.7523693927692385e-01 +2.6813652327002957e-01 +-2.8777271633761763e+00 +-5.0012195896403644e-01 +3.2484074354161291e-01 +-3.6150085643718262e+00 +9.0736164228650551e-01 +3.0938523061337919e-01 +-3.1060929597723685e+00 +-8.6655307187651465e-02 +3.2661082243088729e-01 +-3.3186723921729739e+00 +6.1303005948935774e-01 +3.4362591486304334e-01 +-2.8080756490883791e+00 +-2.1103445334459986e-01 +3.6915121785761834e-01 +-3.5815943294006454e+00 +1.8568411833251286e+00 +4.3548531169888244e-01 +-4.5962594184048324e+00 +1.8568411833251286e+00 +4.3548531169888244e-01 +-4.5962594184048324e+00 +-8.0697810988814955e-01 +3.7328743217070814e-01 +-2.5751883493745464e+00 +-7.1070002982003014e-02 +4.0635902475823804e-01 +-3.2197394085471269e+00 +-3.0888876524022074e-01 +4.9116165533058975e-01 +-3.7185188888032088e+00 +3.3345196881344263e-01 +5.2308569537962291e-01 +-3.4713373140187480e+00 +-2.8094241265352593e-01 +5.7731346692186225e-01 +-3.7291567139009056e+00 +9.8028068413241423e-02 +5.9139455750388070e-01 +-3.2065367432821446e+00 +-1.6758147022095254e-01 +6.2170923940403522e-01 +-3.6389453810923369e+00 +-4.4960808885603309e-01 +5.5292569990272648e-02 +-6.5383069264501892e-01 +6.1755439265538825e-01 +-1.9202649771394131e-02 +-2.8246870864064806e+00 +6.1755439265538825e-01 +-1.9202649771394131e-02 +-2.8246870864064806e+00 +5.0850095139309215e-01 +2.9810417594683693e-02 +-2.7771396802849089e+00 +1.9580284206591596e+00 +2.5503171726029096e-02 +-3.4811413146707704e+00 +7.3829104255971412e-01 +7.9872769099217436e-02 +-2.9286303732903565e+00 +-5.4787789665529196e-01 +1.7658153631943427e-01 +-3.5561360166565050e+00 +2.5397322663232064e-01 +2.2775517388437708e-01 +-4.2588802139289692e+00 +2.4290677379596279e-01 +2.3243156164244441e-01 +-3.9465130927345391e+00 +-7.5965927373741782e-01 +2.7689435883981045e-01 +-2.7667185717225857e+00 +-3.6526684633602113e-01 +3.1161926110075561e-01 +-3.9722177860985735e+00 +6.7091802772072551e-01 +2.9229696013127160e-01 +-2.8422605530179319e+00 +1.8511701426350169e+00 +4.4411653063405143e-01 +-4.5763794976508443e+00 +2.7762600222021133e-01 +4.1538910975727483e-01 +-3.5594805639508569e+00 +4.2678221800444849e-01 +4.0798951759983565e-01 +-2.7815233592489248e+00 +4.6497128264964616e-01 +4.1498497140250568e-01 +-2.8045422144340506e+00 +-7.4174399018000559e-01 +4.2908209865518931e-01 +-2.8456723350386768e+00 +2.1055143688640024e-01 +4.4098608019312163e-01 +-2.7346068554126890e+00 +5.3867988938646549e-01 +4.8157337220731578e-01 +-2.7596643182553677e+00 +3.1716128860123155e-01 +5.5271976831068348e-01 +-3.4866904919527135e+00 +4.1268897374529195e-01 +5.5237359528949836e-01 +-3.3920476398734989e+00 +5.3209752731563886e-01 +5.6360020655269116e-01 +-3.0740972485605189e+00 +4.2990020140305986e-02 +6.3356857232124730e-01 +-3.8694782201135687e+00 +-7.6718852154648709e-01 +5.8516489168418240e-01 +-2.6173888588595426e+00 +-6.4173035698490644e-01 +6.9569839444377957e-01 +-3.4320607670315075e+00 +-3.4058833216056184e-01 +-1.1141281842676388e-02 +-6.6609638416063499e-01 +-8.4025051610640911e-01 +1.0323446843040932e-01 +-2.6476093823941876e-01 +6.6462030128326943e-01 +-7.9701778600111739e-02 +-2.8424246231892605e+00 +1.0436457451702150e+00 +-7.6238861626406904e-02 +-3.2385877343214373e+00 +1.0436457451702150e+00 +-7.6238861626406904e-02 +-3.2385877343214373e+00 +1.6620713143129102e+00 +7.3790714148748868e-02 +-4.0710301798228201e+00 +1.8107691504598009e-01 +1.4904276112252945e-01 +-2.6784157468137546e+00 +8.6813431763100657e-01 +1.6825475796465253e-01 +-3.0279956711755962e+00 +4.0625109930025588e-01 +2.0400554771620852e-01 +-2.8158451323560181e+00 +4.7728362610906244e-01 +2.3720799101008677e-01 +-2.7595877263915245e+00 +4.8323944659942142e-01 +2.4074086499928421e-01 +-2.7853268179021993e+00 +4.8323944659942142e-01 +2.4074086499928421e-01 +-2.7853268179021993e+00 +5.5507388522477741e-01 +2.7702493610346501e-01 +-2.7563358999007139e+00 +4.5019497917973189e-01 +2.9291320253517322e-01 +-2.7935960705310880e+00 +7.1417781479999243e-01 +2.9954703652699949e-01 +-2.8926953132919575e+00 +5.7683696957972075e-01 +3.7678784105345375e-01 +-2.7691777865363210e+00 +2.2337040370325639e-01 +4.8909508673920005e-01 +-4.7128742092895948e+00 +2.8687623298046777e-01 +4.6536878913797236e-01 +-3.5466208561500596e+00 +1.9377146305935014e-01 +4.3191581222264036e-01 +-2.7522980389618614e+00 +3.3008932898326288e-01 +4.6515470589767560e-01 +-2.9925478330259918e+00 +5.3278208940589156e-01 +5.5720988755433265e-01 +-3.1222689773146879e+00 +3.3240600451048724e-01 +5.7491746586114600e-01 +-3.3419102500760403e+00 +2.8154341597501953e-01 +6.5882967565574779e-01 +-4.6584719166040376e+00 +-1.1037656710411289e-01 +6.5852474045814946e-01 +-3.7422372719722041e+00 +-5.6285574028433849e-01 +6.8518104543111935e-01 +-3.4766866545649786e+00 +-5.2055168010499253e-01 +7.5820467604644437e-01 +-3.5939163598301156e+00 +9.8544960146686200e-01 +3.4949533743530575e-02 +-3.1673189892752616e+00 +4.4224856998101769e-01 +6.9597063643588919e-02 +-2.8053374346068689e+00 +1.0445728478637453e+00 +1.5744507278162734e-01 +-3.2374054252647593e+00 +9.1253056126426113e-01 +1.6691409189484516e-01 +-3.0901622710791061e+00 +1.0399518996909727e+00 +2.3722038623768099e-01 +-3.2365778957486162e+00 +9.2746389390642980e-01 +3.5375996977420365e-01 +-3.1120482205888664e+00 +1.8388971107943841e+00 +4.2307604974758101e-01 +-4.5806496287324165e+00 +2.5924700207826568e-01 +4.1321803106441257e-01 +-3.6603236093863987e+00 +3.3403683913906607e-01 +5.8903096564478430e-01 +-3.5331630566595140e+00 +-3.8701455076810082e-01 +1.1117624219310623e-02 +-6.9271624400414367e-01 +6.4940527545070381e-01 +-9.8209356870733580e-02 +-2.8575471204879683e+00 +6.5113414878785159e-01 +-9.1456962211517084e-02 +-2.8049295491731607e+00 +5.9070142635098055e-01 +3.3829028566119766e-02 +-2.7560400301608268e+00 +6.5648879782239233e-01 +9.3415441729818527e-02 +-2.8048043986640003e+00 +7.9753093739428982e-01 +2.2510021221748150e-01 +-2.9564248591445321e+00 +6.9881082424025276e-01 +2.2990440551358857e-01 +-2.8563525261286236e+00 +8.0040175816357939e-01 +2.6612825134676427e-01 +-2.9539644335700004e+00 +1.0397305750369992e+00 +3.7359834678614201e-01 +-3.3538105545210226e+00 +-7.9858443947920044e-01 +3.8219407099565023e-01 +-2.6144611219778811e+00 +1.8293043338879664e+00 +4.8053638565150825e-01 +-4.6022624504201444e+00 +1.8536769721699020e+00 +4.8837308329583129e-01 +-4.6159206646847890e+00 +-8.0062667943264687e-01 +4.2883630201241180e-01 +-2.6145482140568883e+00 +-2.2309224290651164e-01 +5.3615947623485727e-01 +-3.7012602907483152e+00 +3.0463948509442029e-01 +5.9507020986975201e-01 +-3.9250979413981386e+00 +8.8199758646534520e-03 +6.4307561696505799e-01 +-3.7591924585861345e+00 +1.3691563183669555e+00 +1.4201211975546463e-01 +-1.1115338678389384e+00 +1.7997612027191923e+00 +3.5385912559100635e-01 +-6.2735937012129317e-01 +1.4118226596531092e+00 +4.8140790754153298e-02 +-1.0329250404532802e+00 +1.4118226596531092e+00 +4.8140790754153298e-02 +-1.0329250404532802e+00 +1.4079925602513867e+00 +1.2858229509726946e-01 +-9.7654347385673879e-01 +7.8086568350121144e-01 +3.6240844546680562e-01 +-2.8430089389104884e-01 +1.5462726158225870e+00 +3.0008484776727073e-01 +-7.8756185934406842e-01 +1.4590633104596922e+00 +1.1962126533310292e-02 +-1.0215633125347512e+00 +1.4590633104596922e+00 +1.1962126533310292e-02 +-1.0215633125347512e+00 +1.4182175854906793e+00 +1.1721393644425810e-02 +-1.0786846726528461e+00 +1.4182175854906793e+00 +1.1721393644425810e-02 +-1.0786846726528461e+00 +1.4182175854906793e+00 +1.1721393644425810e-02 +-1.0786846726528461e+00 +6.6077469640072339e-01 +9.0596311093535442e-02 +-1.4296348914680508e+00 +1.3761009056807911e+00 +2.7103844299461721e-01 +-1.0509567288022019e+00 +6.8264644229671656e-01 +2.7234034803063417e-01 +-2.0415530037292071e-01 +1.7266588014919133e+00 +2.8336612050886956e-01 +-6.7760444620373250e-01 +1.9259166577865887e+00 +-7.2353738993960998e-02 +-2.2694908598290331e+00 +1.3622192710329502e+00 +4.2024775406491563e-02 +-9.9410992981326685e-01 +1.4628051314007127e+00 +3.8373504445832658e-02 +-2.2235915164844129e+00 +1.3930558365190453e+00 +1.8681139302711952e-01 +-2.2797582232401323e+00 +1.7095339378955938e+00 +2.5645457060012206e-01 +-7.0960377941503017e-01 +1.6623969407754782e+00 +4.3998596820151037e-01 +-8.4534630125879062e-01 +1.9670540413019175e-02 +5.5477518836274065e-01 +-3.5603790531875918e+00 +1.5375044950965655e+00 +5.0789689609651889e-01 +-6.1678207003776087e-01 +-5.5123290481428264e-02 +1.0472343367942687e+00 +-8.0693988703892183e-01 +1.3817806266383637e+00 +-3.3876217431905928e-02 +-1.2144826789891401e+00 +1.3886625311047243e+00 +6.8884455168827324e-02 +-1.0128329600405794e+00 +1.3922816833276588e+00 +1.3897482057647745e-01 +-1.0368487339163452e+00 +1.4065675978805219e+00 +2.4628814376066976e-01 +-2.3013461497763648e+00 +5.6823896633600302e-01 +3.1048992993080027e-01 +-2.8058003707986630e+00 +1.3860089275483920e+00 +2.3026010966207315e-02 +-1.0402858265187345e+00 +1.5577575208457000e+00 +3.1603611719325092e-01 +-1.3847852523205919e+00 +1.4327007596308792e+00 +4.1505158748776244e-01 +-1.2475424997336446e+00 +1.4758474608098384e+00 +4.7676120516530240e-01 +-8.6067202952842525e-01 +3.5325206654068675e-01 +5.4980238823479088e-01 +-3.2115743028098476e+00 +1.5034930497403259e-01 +5.9887161592754912e-01 +-3.2005300088299080e+00 +-4.2356089302951143e-02 +1.2055453286285922e+00 +-8.0604233976130091e-01 +-4.5645713214048134e-01 +-1.2850547811563091e-02 +-2.6109957823241076e-01 +1.2699349405798188e+00 +7.8458137906894914e-03 +-1.0328969963786401e+00 +1.4015015028304254e+00 +-4.3765762937045830e-02 +-2.2912560802565771e+00 +1.3947261429853168e+00 +1.7665712012063069e-02 +-1.1881471428640817e+00 +-4.3221547221755828e-02 +1.1727515034197540e-01 +-6.6551069359063364e-01 +2.7493622351616015e-01 +2.0055999630246998e-01 +1.0340486052240451e-01 +1.3675811261263335e+00 +2.2436545087587145e-01 +-2.3435604375721231e+00 +1.9015782479537859e+00 +5.7419149040442741e-01 +-5.1377006479400533e-01 +1.8952880073937712e+00 +5.8712957045377256e-01 +-5.1159910141987341e-01 +1.3472365855138762e+00 +-2.1948202964701097e-02 +-1.2322674164531664e+00 +1.3472365855138762e+00 +-2.1948202964701097e-02 +-1.2322674164531664e+00 +1.4187921922652786e+00 +1.3249600317415324e-03 +-1.0349639143848208e+00 +1.3626185547273937e+00 +5.0203924286169981e-02 +-2.3497801778136025e+00 +1.6652616403221574e+00 +5.6208532200658669e-02 +-2.2823544576755728e+00 +4.6415380860103178e-01 +7.7732588703380248e-02 +-2.8247545134928820e+00 +1.3675622618684242e+00 +1.3769848234455043e-01 +-1.1022216386546257e+00 +1.5963283418698229e+00 +1.6004719269335468e-01 +-6.8571840545130769e-01 +3.5085988188232706e+00 +8.9011474632012644e-02 +-4.2735791191971808e+00 +1.4984637462237007e+00 +1.9430015251849225e-01 +-6.1647650401769494e-01 +1.4984637462237007e+00 +1.9430015251849225e-01 +-6.1647650401769494e-01 +1.7331516319192817e+00 +2.0329761015298989e-01 +-6.7341723929656705e-01 +5.9763783712252694e-01 +2.2236090285803603e-01 +-1.3317714617445027e+00 +1.5329278611202501e+00 +2.3561036165110544e-01 +-2.2441911611695375e+00 +1.3663065831727257e+00 +2.4166919324523917e-01 +-1.0815275544712217e+00 +1.7785286933187516e+00 +2.4786512575211991e-01 +-6.2306549174619641e-01 +1.1344745936735101e+00 +2.4097874285546711e-01 +-2.0344766856297496e+00 +8.2886765378231797e-01 +2.9526671560189877e-01 +-3.0343487066755257e+00 +2.1849038533952989e-01 +2.8024191829019401e-01 +3.2848610909627035e-01 +1.0593470414666222e+00 +3.6097515179760925e-01 +-3.4301089442449668e+00 +1.5938575112870395e+00 +3.3543656970011976e-01 +-6.9919127994485719e-01 +1.6034532585310146e+00 +3.4252472549719432e-01 +-6.9560108064497039e-01 +1.5706128546709417e+00 +3.4413695039797954e-01 +-7.5825187831027452e-01 +1.6358581234859562e+00 +3.4650668466879053e-01 +-8.0702278494776869e-01 +1.8026200039779303e+00 +3.8338371294669843e-01 +-5.8937427823915167e-01 +1.7391095559982042e+00 +4.1856206791375267e-01 +-6.8428838673842773e-01 +1.7278662984256750e+00 +4.6365529788498300e-01 +-7.1974113532535622e-01 +1.7792304907228733e+00 +4.6608439493507853e-01 +-6.5808996011431764e-01 +1.7312923447837636e+00 +4.7134267482032122e-01 +-6.9381877307654816e-01 +1.8492343903410949e-01 +5.9538957511202362e-01 +-3.2964792396076481e+00 +-1.9148935510943942e-02 +1.0288295786148536e+00 +-7.4481136099858336e-01 +-2.8216968049500600e-02 +1.2937311025451783e+00 +-8.3052612964969796e-01 +1.3576624226659444e+00 +-2.8084978849654500e-02 +-1.1955461565287229e+00 +1.3667443071859979e+00 +-1.4081552798298626e-02 +-1.1424739106287005e+00 +1.4544661576404452e+00 +-1.1562060637446548e-02 +-1.0818032059536256e+00 +1.3631601926642050e+00 +-8.2398842255196180e-03 +-1.0698593561730370e+00 +1.3631601926642050e+00 +-8.2398842255196180e-03 +-1.0698593561730370e+00 +1.4838535849860313e+00 +-5.0230807252938162e-04 +-1.0090635558264884e+00 +1.3678726518645343e+00 +-2.1611827868870930e-03 +-1.0764235743650632e+00 +1.4161900178639839e+00 +3.7930680856086826e-04 +-1.0439068197115533e+00 +1.4499856406106613e+00 +-1.1035118287055041e-03 +-1.0738778370509476e+00 +1.3555435742047395e+00 +-6.1619501154447441e-04 +-1.1178698083601257e+00 +2.0235424713148058e+00 +-9.3719776683142977e-02 +-2.3541408027968318e+00 +1.3674194639023245e+00 +3.1925708313028628e-02 +-9.7933819499840791e-01 +1.4643471331819531e+00 +5.7041597091907370e-02 +-9.4398623174231511e-01 +1.4038728258149020e+00 +6.1281236926975825e-02 +-8.9416452481324171e-01 +1.3870714177676096e+00 +5.4896013274582045e-02 +-1.0301331874734254e+00 +1.3891213867626933e+00 +6.9483777831288479e-02 +-1.0658141457048134e+00 +9.1162805896624244e-01 +1.3327322925220850e-02 +-3.1211918391287390e+00 +7.5060977594931944e-01 +1.5081582990854403e-01 +-1.4780987020180417e-02 +1.3789664984445074e+00 +1.2463960210151603e-01 +-1.1752721080997739e+00 +1.4475252710551432e+00 +9.7151601367515522e-02 +-2.2501264615211261e+00 +1.3891915904595351e+00 +1.4188881938889863e-01 +-1.0071408623326776e+00 +1.5935881101767453e+00 +1.5137653872396947e-01 +-6.7838472632811064e-01 +1.6744365217307333e+00 +1.1954020292171642e-01 +-2.1185081719291672e+00 +1.5276805431159344e+00 +1.2361961983113957e-01 +-2.2544579205228330e+00 +1.3718367554686837e+00 +1.5174836127715877e-01 +-1.1758647702138940e+00 +1.3731225140016492e+00 +1.5695992430558806e-01 +-1.1016293907643850e+00 +1.5987928521483987e+00 +1.7796306924861793e-01 +-6.8844518486590289e-01 +1.5895930640488278e+00 +1.8181484592866734e-01 +-6.8173683807303320e-01 +4.4062145182807848e+00 +1.4790951132547475e-01 +-2.1538656830108027e+00 +4.4062145182807848e+00 +1.4790951132547475e-01 +-2.1538656830108027e+00 +1.3500558389373025e+00 +2.0217270176229332e-01 +-1.0970451912634316e+00 +1.3734157075411362e+00 +2.0285533795791361e-01 +-1.0914586544493303e+00 +1.3565396102717813e+00 +2.1736517614026776e-01 +-1.1944590959484049e+00 +6.1343676645717904e-01 +2.0696577580824213e-01 +-2.8264859057862548e+00 +1.7054124628582958e+00 +2.1763226163058788e-01 +-2.1583380799581229e+00 +1.5653391358431945e+00 +2.1692448114910506e-01 +-2.2485301420962953e+00 +1.5717108994284488e+00 +2.1701532699880821e-01 +-2.2561397789959075e+00 +1.8179358164261703e+00 +2.2835486819436263e-01 +-5.9838161596605410e-01 +5.8282313191020918e-01 +2.3822613544365701e-01 +-2.7927010182800891e+00 +5.8282313191020918e-01 +2.3822613544365701e-01 +-2.7927010182800891e+00 +1.7972747947100813e+00 +2.4619962499674530e-01 +-6.1773990380709742e-01 +1.5989494821715851e+00 +2.4704123604200728e-01 +-6.8953000121793062e-01 +1.3808878326794773e+00 +2.8085399602519823e-01 +-1.0647923610965939e+00 +1.7191681379355113e+00 +3.0277564079920660e-01 +-7.0060136365921677e-01 +1.6050405989068106e+00 +2.9986080080150740e-01 +-6.4859850605297553e-01 +1.7633555566381527e+00 +3.3129536710685592e-01 +-6.1226500403398831e-01 +1.6018965619616010e+00 +3.3422966273934340e-01 +-8.2248992906778895e-01 +1.6515439618394687e+00 +3.3611477593934963e-01 +-7.9200456888452331e-01 +1.3632752611839782e+00 +3.4569613259380327e-01 +-1.2051408662849952e+00 +1.4659881422306031e+00 +3.6836684861917318e-01 +-1.1250260301005639e+00 +2.1476330434945679e+00 +4.4523469939882232e-01 +-2.8750630990270754e+00 +2.0183538045188292e+00 +4.8779756553004411e-01 +-2.8867556089041502e+00 +1.4686504645932852e+00 +4.1133871479356476e-01 +-8.0929937920280171e-01 +1.5004854767210174e+00 +4.1373618782982768e-01 +-7.5873955792990944e-01 +1.6314998242036141e+00 +4.1726229143258786e-01 +-6.7424052766691600e-01 +1.5284914420695312e+00 +4.6969555745203739e-01 +-9.1331590672560059e-01 +1.5386290556619391e+00 +4.5954369558755115e-01 +-6.2454163977583455e-01 +1.8484096639484056e+00 +4.9791275804932056e-01 +-5.3256516786539954e-01 +1.8195867891067092e+00 +5.2418948029344692e-01 +-5.7816859168973977e-01 +2.0456169631504681e+00 +5.4115536542036413e-01 +-6.9174753129144118e-01 +-2.8616209662317937e-01 +5.7507006918798903e-03 +2.5416586496414784e-01 +-2.6959229045659100e-01 +4.4135361300055914e-03 +2.2648130081611628e-01 +-8.0005717122165768e-02 +9.0486001381900272e-02 +-6.9408532697718028e-01 +1.3300605657403279e+00 +7.7636185744091556e-03 +-1.1826944151919823e+00 +1.5863638470700248e+00 +4.0630569242321862e-03 +-1.3551454925236548e+00 +1.3930047422049618e+00 +2.5378655060972359e-02 +-1.0231742005578583e+00 +1.3732848530949380e+00 +2.3660498769993564e-02 +-1.0749267683298764e+00 +1.3911570062987257e+00 +3.1052574254663765e-02 +-1.0168758897757610e+00 +1.3884070711344463e+00 +4.2524912009869305e-02 +-1.0141849666537754e+00 +1.3884070711344463e+00 +4.2524912009869305e-02 +-1.0141849666537754e+00 +1.4053535145233296e+00 +5.3888013607581102e-02 +-8.9008002987690893e-01 +1.5493409058393084e+00 +-7.1555705058032422e-03 +-2.1755103963080509e+00 +1.3955165936349976e+00 +5.5533914453201140e-02 +-9.0059344494026550e-01 +1.3943725989714593e+00 +6.7362161570620430e-02 +-9.0002813834582573e-01 +1.3640392534614014e+00 +7.2352572626527903e-02 +-1.1476076989410025e+00 +1.3654381803107756e+00 +7.2407587500049997e-02 +-1.1678849864904810e+00 +1.3923627333942605e+00 +9.1234656440933204e-02 +-1.0181155274185640e+00 +2.0134754685429361e+00 +3.5257098323307305e-02 +-2.3445098156798707e+00 +1.3665414137019185e+00 +8.7165064116883878e-02 +-2.3580211824111461e+00 +1.5526592444338165e+00 +9.2670113845828364e-02 +-2.2845289538645392e+00 +1.6858380205220638e+00 +9.5294753983742014e-02 +-2.1547878117121901e+00 +6.0021284278284304e-01 +9.9198924928066701e-02 +-2.8285940965533087e+00 +1.5791777039394292e+00 +1.0105967326849126e-01 +-2.2392780181588803e+00 +1.3686957498829988e+00 +1.3589269943973858e-01 +-1.1016966729356668e+00 +7.4042309031363573e-01 +1.8441728139413799e-01 +-3.2115194544335604e-02 +1.4483457049584074e+00 +1.4525033725315717e-01 +-9.5414347614179662e-01 +1.5828488201621782e+00 +1.4930471194185724e-01 +-7.3707687864154103e-01 +1.4109646019069433e+00 +1.5612683064164334e-01 +-9.0919660832480287e-01 +1.4390061883777516e+00 +1.5582761594312042e-01 +-9.8280176258960428e-01 +1.4087735942867050e+00 +1.5977155329688825e-01 +-9.0061089595766852e-01 +1.4739840132505391e+00 +1.7275282915126944e-01 +-1.0101215605534912e+00 +1.3648214558019680e+00 +1.7493757074839961e-01 +-1.1862388506070443e+00 +1.4128541539964385e+00 +1.9810682520476103e-01 +-9.1177672152049616e-01 +1.3947861302073954e+00 +1.8297829678187874e-01 +-2.3718625260164430e+00 +1.9620881274619479e+00 +1.8230172531421135e-01 +-2.3096841940465920e+00 +1.7335285875522668e+00 +2.0440985028171538e-01 +-6.8957299841274089e-01 +1.7335285875522668e+00 +2.0440985028171538e-01 +-6.8957299841274089e-01 +1.3660096099372734e+00 +1.6990217003557584e-01 +-3.6963857197954546e+00 +1.7673439943941993e+00 +2.0717309338291895e-01 +-6.2005762764159500e-01 +1.6400852129784476e+00 +2.0840396091580893e-01 +-7.8115222472483947e-01 +3.2537538168118587e+00 +1.7700434625372535e-01 +-1.9602139133172736e+00 +1.6276985106492314e+00 +1.9472067165279394e-01 +-2.1847223073549444e+00 +1.4108494029554481e+00 +2.3325594197955873e-01 +-9.0301807448416327e-01 +2.3313739115401000e-01 +2.5550270909217054e-01 +3.4033975352223683e-01 +1.4117465257663961e+00 +2.3799209647720099e-01 +-2.2588230393772477e+00 +1.3378392104651591e+00 +2.4928798895359508e-01 +-1.1548863836853782e+00 +1.3378392104651591e+00 +2.4928798895359508e-01 +-1.1548863836853782e+00 +1.4397639205539730e+00 +2.5045583448119246e-01 +-2.2427061279237450e+00 +1.3957525606836909e+00 +2.5526963216110254e-01 +-1.1872354910728311e+00 +1.3949791441526402e+00 +2.9013771429750768e-01 +-1.0074376768708495e+00 +1.4001807223325085e+00 +3.1728159066093214e-01 +-1.2467711202589531e+00 +1.3397316778338075e+00 +3.2214050907877151e-01 +-1.1844940229104246e+00 +1.3577635149795770e+00 +3.2395672211382565e-01 +-1.0791704860642124e+00 +8.9223952168422638e-01 +3.1572141549830263e-01 +-4.4268129530643224e-01 +1.3445956818539253e+00 +3.2823990211853721e-01 +-1.0483807245073888e+00 +1.3920731683476828e+00 +3.3413946989121146e-01 +-1.2559637337023550e+00 +1.3888747876758321e+00 +3.3632936482738918e-01 +-1.0034239302256032e+00 +1.4354759384355793e+00 +3.5222977336370898e-01 +-1.0448577959997101e+00 +1.9609111059516187e+00 +4.5181524175909410e-01 +-3.0208826871607890e+00 +1.4550968212189057e+00 +4.3939029713533756e-01 +-9.1639427070110469e-01 +1.5230132034956034e+00 +4.3591900046210341e-01 +-6.1858983169029835e-01 +1.4587584038269414e+00 +4.5706247832038310e-01 +-9.1786249593091729e-01 +1.4685891737171302e+00 +4.6230577024392544e-01 +-9.0169649246351580e-01 +1.8228552958473747e+00 +5.1036249841121906e-01 +-5.4177964203703854e-01 +2.0759621835598896e+00 +5.9344068785201920e-01 +-7.2852424109154690e-01 +-5.3599538574673013e-02 +4.0734276904731770e-01 +4.9259857463183920e-01 +-1.4062765543869959e-01 +5.6063442534165807e-02 +-7.1023214312263350e-01 +-1.3921249834725888e-01 +5.5943555274340563e-02 +-7.1272106137692770e-01 +1.3973092858617462e+00 +-2.2337233692618624e-02 +-1.1640866939652856e+00 +1.3547664700495914e+00 +2.6837154745567747e-03 +-1.1219293845546712e+00 +1.0129080116650493e+00 +-8.5075989153727175e-02 +-3.2325266576773952e+00 +1.4287637773784017e+00 +1.6788950864661985e-02 +-1.2250777785372475e+00 +2.9039940919191451e+00 +-8.1332731208076131e-02 +-2.2779714229750825e+00 +1.4044152046105587e+00 +3.8792441396893092e-02 +-9.9861603600963000e-01 +1.3959673687135414e+00 +3.5269529599643870e-02 +-1.0222768316740614e+00 +7.6009082217551982e-01 +1.1148287716066144e-01 +-9.2246045504413253e-03 +1.3599835786745063e+00 +4.1501789613378963e-02 +-9.8265839348345196e-01 +1.4194794031051958e+00 +-1.7091209288955779e-02 +-2.2276406308928234e+00 +1.4122627390685909e+00 +4.1513651842515868e-02 +-9.4167811403501045e-01 +7.6070240253350818e-01 +1.1491047671934128e-01 +-6.4532157634797811e-03 +1.3977531218155856e+00 +4.1960026455993261e-02 +-1.0104341841154765e+00 +1.3977531218155856e+00 +4.1960026455993261e-02 +-1.0104341841154765e+00 +2.0294587761036595e+00 +-3.6820793206340283e-02 +-2.3344571427892808e+00 +1.3946969397469220e+00 +4.6085255901924957e-02 +-1.0214471844679649e+00 +1.2243264150556183e+00 +7.3285654337012701e-02 +-8.2561950847922916e-01 +1.3498379297246714e+00 +5.1139056710336403e-02 +-1.2235481271355371e+00 +1.4007877338328445e+00 +6.4940864966733999e-02 +-8.9917189706174805e-01 +1.4007877338328445e+00 +6.4940864966733999e-02 +-8.9917189706174805e-01 +1.6281066925876115e+00 +9.0888580030941343e-03 +-2.2017586108601979e+00 +1.3514174502677245e+00 +5.9993048619834011e-02 +-1.2401287270313004e+00 +1.4040232998636926e+00 +7.2330614268535723e-02 +-1.2143733971718340e+00 +6.6973088848048667e-01 +2.9275834257982788e-02 +-2.8961839544091172e+00 +2.0037501524353947e+00 +4.1137185098827536e-02 +-2.3589259023362588e+00 +1.0682864893799255e+00 +3.3796408199981740e-02 +-3.3223595460140563e+00 +1.3944761837575659e+00 +1.0402617960408486e-01 +-1.0068740308475574e+00 +1.3669650653054939e+00 +1.0293870201158750e-01 +-1.1799727007234200e+00 +1.6860594553613422e+00 +9.5143201545855829e-02 +-2.1396086008458854e+00 +1.3684213024697438e+00 +1.5055525344910434e-01 +-1.0033542140571261e+00 +1.4056636661604545e+00 +1.5230043112383995e-01 +-9.1115092002765352e-01 +1.5990805743128222e+00 +1.1832276068277411e-01 +-2.2163697116926264e+00 +1.4019842395274711e+00 +1.5700645225817753e-01 +-9.4304620488312707e-01 +1.4934500727676736e+00 +1.6944603845113634e-01 +-6.1463322207019788e-01 +1.4294463725114990e+00 +1.0041081652618195e-01 +-3.7044697180466915e+00 +1.3567231764173553e+00 +1.6269136085772262e-01 +-1.1980872323340326e+00 +1.3678366123713381e+00 +1.6629227832097176e-01 +-1.1113252779489169e+00 +1.3566685074397649e+00 +1.6562685690096321e-01 +-1.2302662598063485e+00 +1.3956287575696511e+00 +1.4661132573499400e-01 +-2.2939953324151263e+00 +2.0286492871812554e+00 +1.4975877912801791e-01 +-2.3524765088210779e+00 +7.7257470791279559e-01 +2.1880238864187512e-01 +1.3234410912844099e-02 +1.3717172287631649e+00 +2.0313759062350992e-01 +-1.1328818660660884e+00 +1.2634574059866881e+00 +1.8466112041650787e-01 +-2.2765127316325238e+00 +1.8226689334100061e+00 +2.0772302398247364e-01 +-5.5958215391592425e-01 +1.3281613977924771e+00 +2.0378596487244122e-01 +-2.2919290460794230e+00 +1.4052102907559807e+00 +2.3935892748110460e-01 +-9.1236518726197535e-01 +1.8334132025827363e+00 +2.5023198500980437e-01 +-5.6584635282833851e-01 +1.4044522581790042e+00 +2.5681264659202757e-01 +-9.9512263890844233e-01 +1.3866423254776175e+00 +2.7919101970679588e-01 +-2.2988985476317692e+00 +7.3039333490511371e-01 +2.8529919622215227e-01 +-3.9683632273627423e-02 +1.3544541605061624e+00 +2.9537715561991357e-01 +-1.1287518125371461e+00 +1.7548823517551144e+00 +2.9496302448325851e-01 +-6.3082389680663475e-01 +1.3733095631562995e+00 +2.9692707013902581e-01 +-1.0956800521150725e+00 +1.3628356827760235e+00 +3.1814759556189443e-01 +-1.1378613343739123e+00 +1.7002246110404833e+00 +3.2257804758420067e-01 +-7.0829041211100374e-01 +1.2990719539082232e+00 +3.2258547660466974e-01 +-1.0021277098307049e+00 +1.3821261761133541e+00 +3.3159105638226294e-01 +-1.2799276814647456e+00 +1.3790841785352168e+00 +3.3268919065707309e-01 +-1.2664807981028294e+00 +1.3790841785352168e+00 +3.3268919065707309e-01 +-1.2664807981028294e+00 +9.6995023332773089e-01 +3.1806844903159026e-01 +-4.4520739624672517e-01 +6.8644590376855108e-01 +3.1574045530336814e-01 +-4.2242103336714582e-01 +1.4550540969827273e+00 +3.2846197057171783e-01 +-8.1337391083016886e-01 +1.4713733897567576e+00 +3.2969725633506375e-01 +-7.5846007686347361e-01 +1.4044107990621302e+00 +3.3787497897510554e-01 +-1.1111148984632544e+00 +3.0103132371969137e+00 +4.0044987889256695e-01 +-3.2405730817433405e+00 +1.4292795025195748e+00 +3.5247306650328952e-01 +-1.0533087983135010e+00 +1.4186644229277403e+00 +3.5391327654713967e-01 +-9.1891763124491310e-01 +2.1424305401593888e+00 +4.3198973762235005e-01 +-2.8848221389274959e+00 +3.0204740981507214e+00 +4.6657879795298146e-01 +-3.2429819626977197e+00 +1.5197969991844593e+00 +3.9626841586510791e-01 +-6.3324630083872357e-01 +1.5310231322894330e+00 +3.9682046805241039e-01 +-5.8777771825258429e-01 +1.7760956418921319e+00 +4.0771322348789441e-01 +-6.5021641365867189e-01 +1.7345960443598265e+00 +4.1401712819626152e-01 +-6.8855624948334038e-01 +6.3728630574951894e-01 +3.6454593233016053e-01 +9.6692733456235372e-02 +1.5219609393449496e+00 +4.1333889440774352e-01 +-6.0738664998290315e-01 +2.9988925740822148e+00 +5.4311223710923606e-01 +-3.1948949768091266e+00 +1.8679535143012795e+00 +5.0486760065119485e-01 +-2.9999251330039094e+00 +1.8679535143012795e+00 +5.0486760065119485e-01 +-2.9999251330039094e+00 +1.8785430834462722e+00 +5.1218136134576142e-01 +-3.0255760977900703e+00 +1.5322706951299190e+00 +4.4737214670153957e-01 +-6.2500682726504331e-01 +1.5334960762234824e+00 +4.4739796715950281e-01 +-6.0500755717219290e-01 +1.4721648900074800e+00 +4.6860273053001866e-01 +-9.1691913953842863e-01 +1.4917753511632499e+00 +4.6883365137386340e-01 +-8.3740184807495233e-01 +1.6124394614285258e+00 +4.6946186676566670e-01 +-7.0102402205861947e-01 +1.4754957578983681e+00 +4.8302998005158521e-01 +-9.5201778200260168e-01 +1.6025023008560351e+00 +5.0437739614705601e-01 +-1.0090024891052212e+00 +1.7844791808909299e+00 +5.0931794193980118e-01 +-5.9217950181692258e-01 +1.5377497256563120e+00 +5.0433271209887975e-01 +-5.8752977898365921e-01 +1.7818915186166346e+00 +5.2236104190841681e-01 +-6.5009404659568970e-01 +2.0658237523273604e+00 +5.4324805617814220e-01 +-7.7309227254926016e-01 +1.8182477165317101e+00 +5.2382092142152459e-01 +-5.8226479465188075e-01 +1.6812231608029984e+00 +5.3002139621355293e-01 +-7.5325946824352541e-01 +2.6762915688510053e-01 +6.3423784071500178e-01 +-3.3893180838875092e+00 +1.8103010630388430e+00 +5.6086281417558959e-01 +-6.6242842072623553e-01 +2.0778615568077399e+00 +5.8647952700069894e-01 +-7.4057825063944716e-01 +3.6743625999744538e-03 +1.0495887223349587e+00 +-7.6066291453453416e-01 +8.3215090751940557e-01 +1.4937869335241030e+00 +-2.0301137297998273e+00 +-6.3527079966828978e-02 +1.0485648852423746e+00 +-8.0895948981276455e-01 +-1.7944062377139008e-02 +1.3314387272168453e+00 +-8.3618669541997293e-01 +-5.1396917248737284e-01 +-2.4760917613159506e-02 +-3.4207515351076057e-01 +1.3703034673090078e+00 +-3.4562400202873517e-02 +-1.1248801837168265e+00 +5.7152453623557009e-01 +-9.2317918105647531e-02 +-2.8154086190542467e+00 +2.0166934577434570e+00 +-1.2443645449388384e-01 +-2.3835128746806222e+00 +1.9863671031066852e+00 +-1.1626050860298519e-01 +-2.3544883307932745e+00 +2.9014951475297890e+00 +-1.5224209563219127e-01 +-2.2672277852464382e+00 +1.4260271026485660e+00 +-3.9191705637221901e-03 +-1.0103325191133368e+00 +5.2142431825312907e-01 +-3.3574963753674213e-02 +-2.7967416709102069e+00 +1.3861271666340305e+00 +3.0121514042830373e-02 +-1.0324638245988973e+00 +1.4018538760836492e+00 +3.0946097881912712e-02 +-1.1642492346055373e+00 +1.3734025903354499e+00 +3.9561975087884824e-02 +-1.0803481644010893e+00 +1.3721248800439987e+00 +5.0222877518909456e-02 +-9.9319175329209275e-01 +1.3609692998184404e+00 +5.3627488717151048e-02 +-1.1413454865818917e+00 +1.3859935540379500e+00 +6.0298067091091638e-02 +-1.0320946529517683e+00 +1.6380565624611769e+00 +4.7770062202877064e-02 +-1.1914619980553660e+00 +1.3963593803636496e+00 +6.4584002218378275e-02 +-1.0178943592776670e+00 +1.3905387926557056e+00 +9.3781321807691623e-02 +-1.0145555045201782e+00 +1.4552130249190502e+00 +1.0139366360503477e-01 +-1.0660128656363563e+00 +1.3997573204633020e+00 +1.0119749603769863e-01 +-1.0156139409716922e+00 +1.3533298949660495e+00 +1.0074276518255001e-01 +-1.1624559743621259e+00 +1.6214813390828542e+00 +6.3865956690738385e-02 +-2.1820456535549622e+00 +2.0167244302551928e+00 +5.6422898347217976e-02 +-2.3261255378257983e+00 +1.7163872462779421e+00 +1.2289743018789105e-01 +-7.1182916694140086e-01 +1.4127840486326315e+00 +1.2400636615725437e-01 +-1.2000193232805105e+00 +1.3513977917394329e+00 +1.3184323686013955e-01 +-1.0647560313941276e+00 +2.0188428347608043e+00 +8.2045800668017380e-02 +-2.3288735021267768e+00 +1.3666848429493663e+00 +9.7551616391775037e-02 +-2.3722525930158804e+00 +2.1463444144189892e-01 +2.1085234753403709e-01 +3.1499320106941564e-01 +1.6172370743096003e+00 +1.3165491564403084e-01 +-2.1961947771820363e+00 +1.3686643038640298e+00 +1.6755922332090223e-01 +-1.1495049618214475e+00 +1.3538206493951668e+00 +1.6788744295667535e-01 +-1.2330451929611053e+00 +1.3794907280263446e+00 +1.6679778640653675e-01 +-1.2679924410469019e+00 +1.3548314296302755e+00 +1.6810260025107090e-01 +-1.2577635175001007e+00 +1.3823909082644037e+00 +1.6739868480631884e-01 +-1.2844004387968389e+00 +1.8217056795761883e+00 +1.8259429461231599e-01 +-5.6289521609901016e-01 +1.5698335161965260e+00 +1.7376922515899909e-01 +-2.2323496979818374e+00 +1.7580121183889883e+00 +1.9616097607413016e-01 +-6.4084597967193713e-01 +1.8203872397293948e+00 +1.9760701635795455e-01 +-5.6245725770706045e-01 +1.8203872397293948e+00 +1.9760701635795455e-01 +-5.6245725770706045e-01 +1.6881943309542693e+00 +1.9038766858767531e-01 +-2.1122587469783061e+00 +1.6966871052844121e+00 +1.9005954663961847e-01 +-2.1371832731712450e+00 +1.4937630283873884e+00 +2.3030500897732881e-01 +-6.0178932616004810e-01 +1.6753311744973109e+00 +2.2921756924228920e-01 +-7.3831496813709541e-01 +1.3561247961610736e+00 +2.3264141467144564e-01 +-1.1160389420189913e+00 +1.4943831717316323e+00 +2.3650088060020985e-01 +-6.1004423334577229e-01 +1.7377829897475872e+00 +2.2998586764238949e-01 +-2.1381938386846455e+00 +1.5799107954426512e+00 +2.3376103330316303e-01 +-2.2333139644447604e+00 +1.5075143255449475e+00 +2.5112253299256770e-01 +-5.8818578443009162e-01 +1.6972944667537579e+00 +2.5142774645030203e-01 +-7.2067390502586492e-01 +1.3532594495632051e+00 +2.5263206467285670e-01 +-1.2032448697176228e+00 +1.7537633636805374e+00 +2.5397979198656467e-01 +-6.3878000311490601e-01 +1.3788524775965156e+00 +2.5427399017535424e-01 +-1.0087604022998780e+00 +2.0088461906689146e+00 +2.7590515858650017e-01 +-2.4458238043692480e+00 +2.0064654391108627e+00 +2.8148125741064334e-01 +-2.4524200079864147e+00 +2.0064654391108627e+00 +2.8148125741064334e-01 +-2.4524200079864147e+00 +1.5340923618717002e+00 +2.9601648828045335e-01 +-9.5221891651480683e-01 +1.7739988171102823e+00 +2.9595997415220648e-01 +-6.1989209229630937e-01 +1.4052734961123383e+00 +3.0474235856258591e-01 +-9.2267864224576135e-01 +1.4143664198009955e+00 +3.0780641412121307e-01 +-9.3434823473834006e-01 +1.9059294092622117e+00 +3.3493214061470555e-01 +-2.8537477628211558e+00 +1.4151136571223912e+00 +3.2582685992516092e-01 +-9.2919241837166111e-01 +1.3753513808187490e+00 +3.3385101880330631e-01 +-1.0696063613815561e+00 +8.9475904360286429e-01 +3.1480222111508244e-01 +-1.5483578906251015e-02 +5.0815194079298189e+00 +3.9602015674411623e-01 +-2.5618914807981721e+00 +1.5173501567038488e+00 +3.6464554921808123e-01 +-2.5270910662534574e+00 +1.3656380824150685e+00 +3.4181242810372070e-01 +-1.1603568424245778e+00 +1.4305850055680382e+00 +3.4415288398908700e-01 +-1.0563868049256362e+00 +1.5176097487165374e+00 +3.4666070948757194e-01 +-1.1551780137737131e+00 +1.4165404506680246e+00 +3.4557182923325175e-01 +-9.4280188747143845e-01 +1.4609287958328312e+00 +3.4649059621649847e-01 +-9.9074886690891817e-01 +1.3602416252032248e+00 +3.5032870786693826e-01 +-1.1203343118315923e+00 +1.3628036222404276e+00 +3.5135489169907380e-01 +-1.1143050406268258e+00 +3.0095641629388945e+00 +4.1646609417820601e-01 +-3.2512002049354520e+00 +1.3806473684638338e+00 +3.5311384105501520e-01 +-1.0448601931435979e+00 +1.4181316032491256e+00 +3.6380548330437018e-01 +-1.0080477008616167e+00 +2.1369380158334557e+00 +4.1569254880137019e-01 +-2.8964527423747470e+00 +2.0408590161808857e+00 +4.1723120015596693e-01 +-2.8951296411034377e+00 +-1.2891033706273269e+00 +2.7747125246623389e-01 +1.1376338970339026e+00 +1.7353657598940417e+00 +3.7802803974515253e-01 +-6.8008266287282226e-01 +2.0969219416235485e+00 +4.4937435115594515e-01 +-2.8918129426387695e+00 +1.4280055687525277e+00 +3.9522932759670154e-01 +-9.7055955124593130e-01 +1.5292098641732275e+00 +4.1804125730961328e-01 +-6.1850996065319741e-01 +1.5240939600796566e+00 +4.3954236901201849e-01 +-1.2056758334607811e+00 +1.5427920894681630e+00 +4.3208768073770842e-01 +-9.8350045007453879e-01 +1.5292384277860864e+00 +4.1945178255390991e-01 +-5.9979294868647526e-01 +1.5234840085911998e+00 +4.2026123930949955e-01 +-6.1975976318575343e-01 +1.8854361096410668e+00 +5.2507643522615088e-01 +-3.1099593386571529e+00 +1.5330570088870397e+00 +4.2476321979827936e-01 +-6.5463237519277706e-01 +1.4727059749402340e+00 +4.7337485851844358e-01 +-9.1643116138046266e-01 +1.5237185760792884e+00 +4.7390837935592967e-01 +-7.5587699577595058e-01 +1.5198247584386284e+00 +4.9158932287537954e-01 +-6.2270941823306747e-01 +1.7531442016615522e+00 +5.0771108836736067e-01 +-6.2982973659164732e-01 +1.4277556897005794e+00 +5.5780554659946258e-01 +-1.2972078966683163e+00 +2.3479552144725407e-01 +6.3539321532829363e-01 +-3.5083205921723932e+00 +1.8155487395274270e+00 +5.6121551640058753e-01 +-6.7583736976607001e-01 +2.0809610911848959e+00 +5.8307906661536479e-01 +-7.3710512324396105e-01 +1.8828179009729664e+00 +5.9727577804558607e-01 +-5.1971091662770275e-01 +-1.2613709959762051e-01 +7.6883665928070194e-02 +-7.4126211609829562e-01 +1.3765621712966774e+00 +3.3687531959694934e-02 +-1.0826788906630982e+00 +1.5026426865919107e+00 +1.9866672170397051e-01 +-6.1667884334574574e-01 +1.4268459784893768e+00 +1.8876560834443984e-01 +-2.2611593816812992e+00 +1.6172454850349718e+00 +2.0911719444130153e-01 +-2.2151707312057449e+00 +1.5764524139620462e+00 +2.1571116003070570e-01 +-2.2511770768835624e+00 +1.3527801615381652e+00 +2.4084756293574444e-01 +-1.2378229392612607e+00 +1.4446733351158700e+00 +2.4153170542409161e-01 +-2.2587759977587218e+00 +1.3791891515967387e+00 +2.5917075752208241e-01 +-1.0263728770724656e+00 +1.4421835515692387e+00 +2.7469700698182975e-01 +-2.2450384582055554e+00 +1.3490389777772265e+00 +3.3279918057777075e-01 +-1.1091768545752825e+00 +1.3619996933642078e+00 +3.4073797075683354e-01 +-1.1837024902381834e+00 +1.4144325579460815e+00 +3.4228287513614275e-01 +-1.1872747044233645e+00 +1.3655868107189590e+00 +3.4929574297211069e-01 +-1.1323184809505842e+00 +1.0657792856009318e+00 +3.9204082629340492e-01 +-3.4505947597486166e+00 +2.0587382350174810e+00 +4.0526157711993177e-01 +-2.9271517542484831e+00 +1.4627653061078527e+00 +4.2692508837605725e-01 +-1.1446372967868459e+00 +1.3946129750389520e+00 +4.3312834493169067e-01 +-1.2590121667506957e+00 +2.0878697894685572e+00 +5.1124710307247534e-01 +-2.9582119693733588e+00 +1.4781320881379627e+00 +4.7049308383336674e-01 +-9.0618215274442349e-01 +1.4653017799371566e+00 +4.7188899436343001e-01 +-9.1490588836983133e-01 +3.7431840819204178e+00 +7.4076856388563939e-01 +-2.8237896639896061e+00 +7.9487592261570872e-01 +2.4585341999079330e-01 +-2.9519268424976337e+00 +-1.5412523670649564e-01 +8.8674607027652466e-02 +-7.1056086066556468e-01 +9.0777497900673820e-01 +2.0597027699903023e-01 +-3.0839468442026599e+00 +1.1032261334518050e+00 +2.3511846481931517e-01 +-3.3135838705273484e+00 +6.5689918783520251e-01 +-6.6338414077305438e-02 +-2.7965936674575942e+00 +1.5597197092522892e+00 +2.4326608351380230e-01 +-2.3041969155234350e+00 +-1.5240347372409382e-01 +7.5271436951679052e-02 +-7.0928573134939510e-01 +-4.7412052136133337e-02 +1.3202043156984811e-01 +-6.5257172898832716e-01 +3.9134596581640286e+00 +-9.7315104456534990e-02 +-7.5513672545343544e+00 +1.4613804258578729e+00 +7.1802502495896661e-02 +-2.2152040149521270e+00 +1.5685042121773749e+00 +1.5815751643424591e-01 +-2.2383527632174292e+00 +1.4578194806395048e+00 +1.6993291830603960e-01 +-2.2441376998951577e+00 +1.4446150927107619e+00 +2.9266043887377924e-01 +-2.2716138912066999e+00 +2.0921034381501586e+00 +4.3154779921824021e-01 +-2.9076264624230190e+00 +2.0431759022515426e+00 +4.3937813031923006e-01 +-2.9691191710469051e+00 +2.1014772343220769e+00 +4.3946692249700425e-01 +-2.8900829507424164e+00 +2.1436114222499003e+00 +4.6424277463843849e-01 +-2.8417847699369334e+00 +1.4682762796853606e+00 +-2.3875490442707707e-02 +-2.2090623004413561e+00 +1.4811770094182930e+00 +-1.3042878072236443e-02 +-2.2051407283074917e+00 +-1.4638361916382531e-01 +7.4094805732413629e-02 +-7.1360071886306897e-01 +1.5766065972714942e+00 +6.5684780912908372e-02 +-2.2374018094703110e+00 +1.4413739441842335e+00 +6.7450157689941309e-02 +-2.2546122766774390e+00 +1.4145086161138429e+00 +6.7813631836089586e-02 +-2.2815080268977717e+00 +1.5670097325283081e+00 +7.2351372061406363e-02 +-2.2353280612839379e+00 +1.4033234630776630e+00 +7.2357002335298848e-02 +-2.2842050456560088e+00 +1.4165113139020540e+00 +8.4944797418682244e-02 +-2.2730634925670596e+00 +1.4412780765305098e+00 +1.9172566626330770e-01 +-2.2436700921538137e+00 +1.5516882708883259e+00 +2.2006200054343070e-01 +-2.2707706303572368e+00 +1.5641354802449952e+00 +2.2114686255231747e-01 +-2.2540209508010247e+00 +2.1154080477047850e+00 +4.2296802934668987e-01 +-2.8733982487237153e+00 +2.0396584471731654e+00 +4.3683737886024732e-01 +-2.9787035565983651e+00 +2.0963343070441809e+00 +4.6520739962659607e-01 +-2.9054468120474648e+00 +1.4668658778298733e+00 +-3.2110357336327902e-02 +-2.2071709561953634e+00 +-5.7752155772571943e-02 +6.0280733371897453e-02 +-6.3259661154865487e-01 +1.5695825701295254e+00 +9.4563514494677259e-02 +-2.2370436209615656e+00 +1.5572982549007066e+00 +9.4590921045755408e-02 +-2.2493827480293533e+00 +1.5695151156951641e+00 +9.7943995280351942e-02 +-2.2347834720930488e+00 +1.4421709495653288e+00 +1.6559571359424899e-01 +-2.2550508915864316e+00 +1.4408399504217373e+00 +1.8996722371816790e-01 +-2.2462652097570754e+00 +1.4534980973692759e+00 +2.5676054629629824e-01 +-2.2419065441906039e+00 +1.4423009213933362e+00 +2.5827435472480531e-01 +-2.2612782290663751e+00 +1.4503243658564264e+00 +3.0915339775238310e-01 +-2.2530931068769733e+00 +2.1166639599117265e+00 +4.2528579211675410e-01 +-2.8688768166877763e+00 +2.0377308793513089e+00 +4.3853419262434346e-01 +-2.9806573143909332e+00 +2.0763214388676263e+00 +4.3970095142996468e-01 +-2.9251705897173381e+00 +2.0718016478134729e+00 +4.4421380466761501e-01 +-2.9321542192332344e+00 +2.1412225647111987e+00 +4.5304831239241949e-01 +-2.8510211954945239e+00 +2.1168879862291945e+00 +4.6200025897305491e-01 +-2.8717869952546420e+00 +2.1169149351426970e+00 +4.6225163073598524e-01 +-2.8762870445122011e+00 +1.4718258450297115e+00 +-3.2210139805395589e-02 +-2.2064293903861154e+00 +1.4651285241734602e+00 +-1.1597521850578137e-02 +-2.2088000139260409e+00 +1.5662775720245150e+00 +7.0222277330271227e-02 +-2.2387654900796603e+00 +1.7105521855386372e+00 +2.1791066759489636e-01 +-2.4106096968255550e+00 +1.4476233887960728e+00 +2.4109075572318434e-01 +-2.2615821781355674e+00 +2.1424526211582440e+00 +4.1862741204157133e-01 +-2.8421360535313194e+00 +2.0793056212029430e+00 +4.2056415637599470e-01 +-2.9158844224613185e+00 +2.0896890777007378e+00 +4.2440360753843764e-01 +-2.9090494203476327e+00 +2.0856427128887733e+00 +4.2448435457361361e-01 +-2.9111611988406474e+00 +2.0864615805639182e+00 +4.2882040952164696e-01 +-2.9126470962223050e+00 +2.0905856720862444e+00 +4.3036308283937796e-01 +-2.8997955828001860e+00 +2.0731068972866722e+00 +4.3334892534353314e-01 +-2.9264560817585048e+00 +2.1415127942049685e+00 +4.3267118983549696e-01 +-2.8443891420043776e+00 +2.0676729660767030e+00 +4.3380453217363901e-01 +-2.9305857456170945e+00 +2.0724399206699453e+00 +4.3747038628647011e-01 +-2.9284641779158229e+00 +2.0938055744853070e+00 +4.4881213109207957e-01 +-2.8916397881844182e+00 +2.0773120524546571e+00 +4.5663764579577126e-01 +-2.9237532997925419e+00 +2.1031808681395154e+00 +4.5811353453579279e-01 +-2.8960923825858700e+00 +2.1023779157588267e+00 +4.6244195252388670e-01 +-2.8957508265644192e+00 +-7.7478919916874722e-02 +5.9820210036350699e-02 +-6.4593902592295060e-01 +-1.3086840137822631e-01 +5.9404537993235453e-02 +-6.8477416362291676e-01 +1.4424214037968284e+00 +9.9372896865589491e-02 +-2.2550370580072392e+00 +1.4051267723936103e+00 +1.6587842848123624e-01 +-2.2946470834088109e+00 +1.5725950171828547e+00 +2.1169972721514457e-01 +-2.2407890808367537e+00 +1.5439508021522590e+00 +2.1218932136966456e-01 +-2.2731311878603382e+00 +1.5728736950917741e+00 +2.2705274459465180e-01 +-2.2416282738837809e+00 +1.4588766264275372e+00 +2.7781145466374363e-01 +-2.2249312764562923e+00 +2.1245888186786885e+00 +4.2550239843588106e-01 +-2.8664966019301046e+00 +2.0883034746138431e+00 +4.2630926829821270e-01 +-2.9057996787958884e+00 +2.1245728699549593e+00 +4.2769556185265589e-01 +-2.8674007044482832e+00 +2.1446098331734937e+00 +4.2880168166888250e-01 +-2.8405106532762843e+00 +2.1023527604063199e+00 +4.3241470412839694e-01 +-2.8919234240359271e+00 +2.0914272564853644e+00 +4.3302787742159943e-01 +-2.9065905560146374e+00 +1.9401874012988136e+00 +4.2879579532508277e-01 +-2.8827716979036717e+00 +2.0781545740024754e+00 +4.3771299742230557e-01 +-2.9268479993726357e+00 +2.0732550991848022e+00 +4.4170850369697851e-01 +-2.9200752514915447e+00 +2.0750979648976893e+00 +4.4223679326269089e-01 +-2.9270900449689683e+00 +2.0788865081451346e+00 +4.4627892133315156e-01 +-2.9222387537910937e+00 +2.0770654916294435e+00 +4.4629868502369879e-01 +-2.9242657604240896e+00 +2.0989766706822701e+00 +4.5176575966922722e-01 +-2.8978035284164041e+00 +2.0761732494929408e+00 +4.5494382172955211e-01 +-2.9265224739385980e+00 +2.1009021637075285e+00 +4.6430497998005743e-01 +-2.8968984916167115e+00 +2.0715344708472658e+00 +4.6584434982807243e-01 +-2.9305016084800477e+00 +-5.6741278826081776e-01 +1.4697784000708541e-01 +-3.0605698242661519e+00 +-1.4608369690047192e+00 +5.7273471948154231e-01 +-2.3205666850964510e+00 +-1.0921248685986289e+00 +4.3510774653460571e-01 +-2.3426881839869340e+00 +-1.1976138062133808e+00 +5.9838486501140531e-01 +-2.3101085718238918e+00 +-1.5119571187995497e+00 +6.0220952069340594e-01 +-2.3395751453294813e+00 +-1.2743747267731846e+00 +5.4974764428395433e-02 +-2.4233881921068430e+00 +-1.2785432617836225e+00 +1.7197209203773309e-01 +-2.3398569044402331e+00 +-7.3837485113126655e-01 +2.1274123555411939e-01 +-2.5925986778845238e+00 +-1.1017629974235701e+00 +3.3041327888011940e-01 +-2.3604722493012353e+00 +-1.1206728892046476e+00 +4.1053969003741286e-01 +-2.3468033607406800e+00 +-1.2025995294365019e+00 +4.7561554509042375e-01 +-2.3255954884031618e+00 +-7.2609125618888459e-01 +5.7716714288087134e-01 +-2.6876335360119490e+00 +-9.3319388255083124e-01 +6.4410917018737490e-01 +-2.5106251805885327e+00 +-1.4212676471307839e+00 +6.2745265724162880e-01 +-2.3406969411412808e+00 +-9.6648635086322865e-01 +6.9225300085168651e-01 +-2.3799635002418116e+00 +-1.1842460336547380e+00 +8.0097172643147030e-01 +-2.3554016484722786e+00 +-1.0293810882029695e+00 +6.8339124721196187e-02 +-2.3217813251853090e+00 +-8.2611647244941833e-01 +1.4880795097007216e-01 +-2.5723995060913896e+00 +-1.1856477057209454e+00 +1.8863477181348565e-01 +-2.3083769043079720e+00 +-1.1856477057209454e+00 +1.8863477181348565e-01 +-2.3083769043079720e+00 +-7.3124694426334003e-01 +2.5454999402751716e-01 +-2.6828009287366421e+00 +-8.5539299122732970e-01 +4.0663001882523692e-01 +-2.5250404024863093e+00 +7.5711988949624956e-02 +5.3108118678048721e-01 +-3.0751118335958214e+00 +-1.1797054909936169e+00 +4.1184618377159404e-01 +-2.3135042858133827e+00 +-1.4122240526581753e+00 +6.4044486458815364e-01 +-2.2973681119461276e+00 +-1.3000792087426505e+00 +1.4651562310603949e-02 +-2.2781497213678801e+00 +-1.1755610605736373e+00 +1.2587789688954806e-01 +-2.2622646287416006e+00 +-1.1755610605736373e+00 +1.2587789688954806e-01 +-2.2622646287416006e+00 +-7.6199051387473571e-01 +1.7569968018963839e-01 +-2.4013014296226465e+00 +-1.8743220704875913e-01 +3.8510015285137600e-01 +-3.5755584829374456e+00 +-1.1773082802717239e+00 +2.8598442450804001e-01 +-2.3342885228562484e+00 +-1.2080720174115087e+00 +2.8403295600459333e-01 +-2.2987532018265573e+00 +-2.1280218430078415e-01 +4.5511054121638100e-01 +-3.5869210980401505e+00 +-1.3762098943334899e-01 +4.9430362358316748e-01 +-3.6178588413905022e+00 +-9.5343859436976208e-01 +4.0745603798088315e-01 +-2.4403677256948662e+00 +-1.5751009948345811e+00 +5.8004053365982100e-01 +-2.3828737685722627e+00 +-9.6419532848291944e-01 +6.6090139192106667e-01 +-2.4990972996120484e+00 +-9.8091579061583867e-01 +1.0894538172697345e-01 +-2.5093668242622877e+00 +3.6438622127830132e-02 +5.5115282685982403e-01 +-3.0482493506053907e+00 +-1.1003896282979686e+00 +4.4782786324585055e-01 +-2.3512510741034367e+00 +-1.3212826232685337e+00 +6.7513293504285754e-01 +-2.3293218121904644e+00 +-1.1053746801522384e+00 +6.9212688947670431e-01 +-2.3345330040801873e+00 +-1.3470887762137911e+00 +5.1320545026538211e-02 +-2.4819854322538233e+00 +-1.0636177812897361e+00 +2.0678888885265961e-01 +-2.2875503016917023e+00 +-1.2829491625737763e+00 +2.1883796633136787e-01 +-2.3336172591442921e+00 +-3.8000631943934798e-01 +7.0776449282972553e-01 +-4.6857327503937780e+00 +-9.0387610217392600e-01 +4.5970309847493479e-01 +-2.5153031497135330e+00 +-1.3581478843455785e+00 +5.8999585266737209e-01 +-2.2991647490316067e+00 +-1.0988174755883677e+00 +6.7427667823797321e-01 +-2.3344523466544458e+00 +-9.9885094137592700e-01 +6.9531548247424202e-01 +-2.3938051196122734e+00 +-1.0605298447509164e+00 +7.1646777504463954e-01 +-2.4975389576952463e+00 +-1.1044831735457568e+00 +7.9181769827654991e-01 +-2.5318759695097666e+00 +-1.2612723230139162e+00 +-2.4262072914737053e-02 +-2.2569253246208114e+00 +-1.2784260891166739e+00 +2.6184686721707481e-02 +-2.4991422327270318e+00 +-8.8736490678737723e-01 +3.6918367192280178e-02 +-2.4660552031845189e+00 +-8.7937061140103523e-01 +5.3621054436823135e-02 +-2.3129100004084586e+00 +-9.0108962173863216e-01 +5.4617727239427330e-02 +-2.2932067526539144e+00 +-1.0481642363303953e+00 +7.7711340916627014e-02 +-2.2598801023641921e+00 +-1.1647150290727040e+00 +9.1644826915473987e-02 +-2.3640750285210954e+00 +-7.7471902089071742e-01 +1.3892674367278515e-01 +-2.3894403250877927e+00 +-3.7324957789202207e-01 +2.7372577741353882e-01 +-3.7233729307934453e+00 +-1.1722448082473917e+00 +2.0162806931068100e-01 +-2.3523700731604866e+00 +-1.1214978020365036e+00 +2.4831279148058119e-01 +-2.3445960143960334e+00 +-8.5217249062403411e-01 +2.7662580679550619e-01 +-2.5682199618128285e+00 +-1.3989063905227558e-01 +4.3585038726146597e-01 +-3.5132058985728976e+00 +-7.3285291682065368e-01 +3.2520780265430405e-01 +-2.6111630313786320e+00 +-3.2720499416834366e-02 +4.3320959436891643e-01 +-3.1336548672297684e+00 +-7.6899792209060225e-01 +3.6237543447284498e-01 +-2.5371420902150947e+00 +-8.5704883735101145e-01 +3.6805639530534334e-01 +-2.5041376548685728e+00 +-2.0340836910510826e-01 +5.8996829742531542e-01 +-3.7577977987839537e+00 +-9.3291429120506109e-01 +3.8489558483298247e-01 +-2.3118135809099343e+00 +-6.4907719701965561e-01 +5.9546177917474630e-01 +-2.9681410039487712e+00 +-1.0054831231429673e+00 +5.3423913262998035e-01 +-2.3646513482050349e+00 +-1.2596684799918290e+00 +5.3445953695228565e-01 +-2.3054244150051422e+00 +-1.4709529762348024e+00 +5.9280236829262190e-01 +-2.3353119558904845e+00 +-1.2376498421727302e+00 +6.0297737538710450e-01 +-2.3854444935239045e+00 +-1.1755931002196027e+00 +5.9249383385941601e-01 +-2.3170317305028560e+00 +-1.3898008900369598e+00 +5.9934337342541766e-01 +-2.2848404317528370e+00 +-8.9903785289408400e-01 +7.3628030907205289e-01 +-2.5959995123167037e+00 +-9.7937525688777738e-01 +6.9454912431720428e-01 +-2.3913066115374324e+00 +-7.5743870458074036e-01 +8.7151129878555156e-01 +-2.9639410298654489e+00 +-1.1213654876619548e+00 +7.3887945704576918e-01 +-2.4755991307724781e+00 +-1.1332316523813901e+00 +7.6544382687773416e-01 +-2.4864296462549840e+00 +-1.1433575271839571e+00 +7.5429294285126769e-01 +-2.3586344157940995e+00 +-1.3532174427352495e+00 +1.3290354451976145e-02 +-2.4958537582170770e+00 +-1.1425637743209984e+00 +5.6048704172048033e-02 +-2.2497564483385566e+00 +-1.2840064279565180e+00 +8.1001541463890922e-02 +-2.2486929930635799e+00 +-1.2890933292972460e+00 +8.5392282587564788e-02 +-2.2533663960183974e+00 +-1.2923065947038013e+00 +9.2358493142499415e-02 +-2.3297694536212479e+00 +-1.2327297860754343e+00 +9.5054095876481615e-02 +-2.2763293903350781e+00 +-7.9741115259488482e-01 +1.0942615593789329e-01 +-2.3553004188329725e+00 +-4.1172684026901246e-01 +1.6199504821570646e-01 +-3.3711260758904693e+00 +-7.3580208286365179e-01 +1.5960171772150375e-01 +-2.6925459477841076e+00 +-1.1099922017547270e+00 +1.3671448479519496e-01 +-2.2591611515036556e+00 +-1.3128618052923560e+00 +1.5368447054827863e-01 +-2.3434987825957316e+00 +-3.9760860400968229e-01 +2.9616203645716555e-01 +-4.0485105442454037e+00 +-3.9573222674627045e-01 +2.9677798610314954e-01 +-4.0667099315163764e+00 +-1.1684903350483171e+00 +1.7483174801966769e-01 +-2.2814196752433396e+00 +-9.8276874875644182e-01 +2.0071457580880966e-01 +-2.4798208414668252e+00 +-1.1006363179204095e+00 +1.9938746592121090e-01 +-2.3588800856780625e+00 +-1.0853033804013903e+00 +2.0714042296334967e-01 +-2.3795819904292683e+00 +-1.2311544001169510e+00 +1.9941917706136403e-01 +-2.3022589063044130e+00 +-1.0643809916018072e+00 +2.1833347616586643e-01 +-2.3831921765689139e+00 +-4.0764340528311349e-01 +3.8097651214134221e-01 +-4.0901528111256642e+00 +-1.2186298857584177e+00 +2.2296423594196876e-01 +-2.4101899540983647e+00 +-2.2549486744472808e-01 +3.7028952896238188e-01 +-3.7387868334378496e+00 +-4.6103465077567191e-01 +4.4812263462040974e-01 +-4.2073471813541499e+00 +-1.1108734706560912e+00 +2.4774025186451387e-01 +-2.2802522302189652e+00 +-1.1885741458165404e+00 +2.5181616282682528e-01 +-2.2871928846392833e+00 +-4.0140567893408058e-01 +4.9730273765945349e-01 +-4.1116359214131952e+00 +-2.1174500948969127e-01 +4.4948955138919394e-01 +-3.6427288007616161e+00 +-2.0329681881711767e-01 +4.4914791420890327e-01 +-3.5801189825872557e+00 +-4.8843317408083994e-02 +4.2496139405488531e-01 +-3.1118913181952426e+00 +-2.8978939469620196e-01 +5.1321409752108949e-01 +-3.8809576626746383e+00 +-1.2118585617529496e+00 +3.1017475310786741e-01 +-2.3009184650960113e+00 +-3.0373167987065125e-01 +6.2424551516211380e-01 +-3.8912115414477140e+00 +-5.4266066531211993e-02 +6.5193438259384928e-01 +-3.8079605911508732e+00 +-1.1249237798810245e+00 +4.3303808259750581e-01 +-2.3113150069155504e+00 +1.4328588517987090e-01 +6.0773972245350505e-01 +-3.1703825702188131e+00 +-1.2900049189159657e+00 +6.0094586819252171e-01 +-2.3579568871184269e+00 +-1.4818142674033181e+00 +6.2397613256849283e-01 +-2.5017216976706771e+00 +-1.3989086270337090e+00 +6.0258739809605089e-01 +-2.2820679070087095e+00 +-1.2694911163566722e+00 +5.3262936109083880e-01 +-1.9955435591118598e+00 +-7.9528360168422318e-01 +7.0470497835323653e-01 +-2.6571522132643834e+00 +-1.1967373543198567e+00 +6.3821796119407626e-01 +-2.3535445123498571e+00 +-1.2934386051218287e+00 +6.6276226773173297e-01 +-2.4103371208121991e+00 +-9.5914244394134784e-01 +7.1929071030953207e-01 +-2.5376991057448266e+00 +-9.9356784695913236e-01 +7.9647560315993970e-01 +-2.6375401466328081e+00 +-1.1965437410588999e+00 +7.4365475020748029e-01 +-2.3253037101280101e+00 +-1.1277438159696400e+00 +2.1205152526221802e-01 +-1.5582618096456999e+00 +-1.2432501132596590e+00 +4.4131318339691272e-01 +-2.2911610319049691e+00 +-9.2046574050052365e-01 +4.2511145305835762e-01 +-1.4225301795085576e+00 +-6.9314777739344080e-01 +1.5117489775769877e-01 +-1.3979078264868532e+00 +-1.1121957685770878e+00 +1.7241073545566513e-01 +-1.3027641535647141e+00 +-1.2842479740900379e+00 +3.5594629441718056e-01 +-1.4034915019615204e+00 +-1.0364893559549566e+00 +4.4028634854003068e-01 +-1.4456330252645511e+00 +-9.0512876803128695e-01 +5.0471470284434072e-01 +-1.4129532607303343e+00 +-1.2859461860294226e+00 +3.3230594943099684e-01 +-1.4791237612655459e+00 +-1.2840859303465899e+00 +4.0536013537817323e-01 +-2.2932961994409173e+00 +-1.4499619007369873e+00 +5.3879232404556876e-01 +-2.2786070129978202e+00 +-1.1473338051073008e+00 +-4.2654816737284643e-03 +-1.7088728026559803e+00 +-1.2546476692249946e+00 +1.7248967151934738e-01 +-2.4733754390415488e+00 +-1.0662017713856906e+00 +1.7653764824980803e-01 +-1.6512431880800063e+00 +-1.0662017713856906e+00 +1.7653764824980803e-01 +-1.6512431880800063e+00 +-1.0739889797155635e+00 +4.3253312516635434e-01 +-1.4558339023474176e+00 +-1.1611452788352432e+00 +8.5090487001475437e-02 +-1.6497376152049514e+00 +-7.5467467850531922e-01 +1.6157379434618763e-01 +-2.6832900205980890e+00 +-8.0466649725743378e-01 +1.6910891032582731e-01 +-2.7716990928885377e+00 +-2.6802673831856256e+00 +7.9202436635472651e-01 +-2.7805413165818273e+00 +-1.1645001411493052e+00 +2.4340256794097744e-02 +-1.6672089945208033e+00 +-1.1781568840724082e+00 +4.3860269972097313e-02 +-1.6901728509530991e+00 +-7.4020554200901278e-01 +2.0092378356905888e-01 +-2.7808352126727773e+00 +-9.4492619563367131e-01 +3.2987172250275870e-01 +-2.5227542274541372e+00 +-1.6808448270207568e+00 +7.2939462608780736e-01 +-2.5015984900800179e+00 +-1.1857769419070772e+00 +4.2772656011484951e-02 +-2.4929804458817961e+00 +-7.3673395537944153e-01 +3.2092236965707144e-01 +-2.7355379979972554e+00 +-8.9472871790258213e-01 +2.6436204077270203e-01 +-1.5716954411421078e+00 +-1.0072340684823997e+00 +2.9635359181035942e-01 +-1.6062086004284659e+00 +-1.0072340684823997e+00 +2.9635359181035942e-01 +-1.6062086004284659e+00 +-7.1917253057866382e-01 +4.3369215476330392e-01 +-2.7251784693961167e+00 +-7.1690474414109151e-01 +4.3413591527170603e-01 +-2.6125349809326073e+00 +-1.4102692830334416e+00 +4.4972605050484271e-01 +-2.2853498001791985e+00 +-9.3706188845185090e-01 +4.9132605333178964e-01 +-1.4252095028262015e+00 +-1.2882033571789766e+00 +1.3596921034198038e-03 +-1.5377421588949176e+00 +-1.1573396489147902e+00 +3.6751758187892815e-02 +-1.6791354644526404e+00 +-1.0932108718651106e+00 +4.1143907452993046e-02 +-1.6438017047152695e+00 +-1.0963105187765934e+00 +4.1047023752264468e-02 +-1.7060769755105802e+00 +-1.1251078013504767e+00 +6.5357233419802402e-02 +-1.2495686589294530e+00 +-1.1559553293888403e+00 +6.2481609026706297e-02 +-1.6403847147250858e+00 +-1.1463908560162728e+00 +1.1339347126209859e-01 +-1.6181743216683540e+00 +-1.1443704353021733e+00 +1.2937428829281467e-01 +-1.6090965232866434e+00 +-1.0420532793435802e+00 +1.8208293305609743e-01 +-1.6990004556895808e+00 +-9.5327096124904831e-01 +2.4776732401505247e-01 +-1.5690743938012248e+00 +-7.2985248463592700e-01 +3.4173281781649023e-01 +-2.7464069387349035e+00 +-7.1633914604136950e-01 +3.4643263543354269e-01 +-2.7048057749772823e+00 +-1.1411287296760615e+00 +3.1266843712951742e-01 +-1.5903676978660501e+00 +-1.1871044167753113e+00 +5.7828730843348575e-01 +-2.2555207318083332e+00 +-1.0694166646545256e+00 +4.9754183316720157e-01 +-1.4184973482826524e+00 +-1.1358746652615677e+00 +8.7688653546494377e-01 +-2.3622318265080380e+00 +-1.1359823326520142e+00 +6.2229941318535410e-02 +-1.2519909921445203e+00 +-1.1535982212716589e+00 +3.6727308064790770e-02 +-2.5019609065339017e+00 +-1.1562485214654978e+00 +6.0305579032358711e-02 +-1.6738528065526570e+00 +-1.1602728750085940e+00 +7.1506695781900886e-02 +-1.6617496287453910e+00 +-1.3958551075544907e+00 +8.8945667579841500e-02 +-2.4603326778763721e+00 +-1.2392064815604567e+00 +8.9550966921919925e-02 +-2.4454146988314824e+00 +-1.1559791201618852e+00 +1.0171973827682131e-01 +-1.6287338039685137e+00 +-7.0251592209137337e-01 +1.0183160612952646e-01 +-1.4848531911376557e+00 +-7.5163663231614142e-01 +1.0721838889380560e-01 +-1.5028812501364794e+00 +-1.1461259956646417e+00 +1.1693945032405230e-01 +-1.6362517531336205e+00 +-1.3352541245315892e+00 +1.6945745138099691e-01 +-2.4393259007243779e+00 +-6.9749989807457236e-01 +1.5638035029150610e-01 +-1.3973460197513790e+00 +-1.1358354789527305e+00 +1.8223273706514756e-01 +-1.7164630736454600e+00 +-8.4997764525051267e-01 +1.9675148145063082e-01 +-2.6609343513732608e+00 +-7.3662486899906088e-01 +2.0083710292707349e-01 +-2.8644965420815360e+00 +-1.1355220895332327e+00 +2.2069593461466416e-01 +-2.4331887872694056e+00 +-8.1853047839877346e-01 +2.7393669731766934e-01 +-2.6520228335522105e+00 +-1.3216396903818792e+00 +3.1714322808341011e-01 +-2.4230231266722884e+00 +-1.1977418573317524e+00 +4.0904047941820659e-01 +-2.3937809450448753e+00 +-7.9054053784676170e-01 +4.1359464117294548e-01 +-2.5709709490261998e+00 +-9.9813219299972455e-01 +3.5739452616707534e-01 +-1.5324693091680897e+00 +-1.4102575959704979e+00 +4.9262380493943875e-01 +-2.4195559951342189e+00 +-1.4227541255295806e+00 +5.3546875880495715e-01 +-2.3902916146508484e+00 +-8.9910254713025517e-01 +4.1254101030355628e-01 +-1.4424571293239161e+00 +-7.6470715908848463e-01 +5.7556059949820504e-01 +-2.5227890884843998e+00 +-7.6470715908848463e-01 +5.7556059949820504e-01 +-2.5227890884843998e+00 +-8.8720746567865350e-01 +5.9159478553193035e-01 +-2.4154109480559569e+00 +-2.6414419128573909e+00 +8.2969064721508357e-01 +-2.7928138855550291e+00 +-2.5849637211682381e+00 +8.3511691618812545e-01 +-2.8184939483186224e+00 +-9.2252943255084729e-01 +4.9901624188245591e-01 +-1.4075222627772355e+00 +-2.1943574313911203e+00 +6.7554833358512256e-01 +-1.7059065803731785e+00 +-9.6165556567803478e-01 +5.1794441852237172e-01 +-1.3991481085026762e+00 +-1.1445388610079281e+00 +6.9848082112889698e-01 +-2.3425019598276466e+00 +-1.2277666894830286e+00 +7.0892983704936097e-01 +-2.2588474554145859e+00 +-1.0002785235276714e+00 +7.7072870990758080e-01 +-2.4611869368605119e+00 +-1.2894039278894591e+00 +2.6680822937699294e-03 +-1.5270304815018956e+00 +-9.7260999062197317e-01 +9.5706371020160746e-02 +-1.6839632108017208e+00 +-1.2856281414058224e+00 +1.0053048012675758e-01 +-2.4490428316860919e+00 +-1.1573810856674394e+00 +1.1225912434050378e-01 +-1.6334428583397005e+00 +-1.1441529430439423e+00 +1.2069239352235259e-01 +-1.6272357790855785e+00 +-1.2927011276645406e+00 +1.6324050943641549e-01 +-2.4509326311658675e+00 +-7.7872604606982099e-01 +1.6470642826934295e-01 +-2.8078949102645701e+00 +-1.0674436778984802e+00 +1.7554800157833242e-01 +-1.6971414015212867e+00 +-1.2772669416881135e+00 +2.2781713096009387e-01 +-2.4267685746160428e+00 +-8.0294449310892935e-01 +2.6740581191481694e-01 +-2.6564800684355130e+00 +-1.1891514259473628e+00 +3.2720803045131691e-01 +-2.4123682466306637e+00 +-1.2136197648408276e+00 +3.2856440112770779e-01 +-2.3989301428962855e+00 +-7.9290599933666039e-01 +4.0389897832012656e-01 +-2.5918320599046187e+00 +-1.1490565679440978e+00 +3.4952662115855571e-01 +-1.5586318884941166e+00 +-8.1871993637737439e-01 +3.2813417539963763e-01 +-1.4774908426137379e+00 +-9.0180508145690330e-01 +4.7578895666627846e-01 +-2.4560695398410317e+00 +-1.5315102254155804e+00 +5.2363772679854059e-01 +-2.4336773029520558e+00 +-7.8343016170775492e-01 +5.0593210311599823e-01 +-2.5130633251302519e+00 +-1.1848520194403331e+00 +4.2866432557478501e-01 +-1.5129794991325987e+00 +-1.1132191969827272e+00 +6.0452426222096312e-01 +-2.3490485076488441e+00 +-1.6904313682767707e+00 +6.7591497451655247e-01 +-2.4573801974171681e+00 +-8.6846506029955972e-01 +6.3157014551473034e-01 +-2.4217963949888199e+00 +-1.0948018522842118e+00 +5.1590729360283405e-01 +-1.4127421999294978e+00 +-1.2983626559600288e+00 +7.0558920292206639e-01 +-2.3908729799655823e+00 +-1.2432853987907402e+00 +7.2237816456783721e-01 +-2.3630125707551843e+00 +-1.1081649226781631e+00 +6.8845875924557742e-01 +-2.2700331154744462e+00 +-1.1824505880211986e+00 +7.3363114387135131e-01 +-2.3442143473429256e+00 +-1.0057990162851811e+00 +7.2920049678525256e-01 +-2.3874820458335790e+00 +-1.9799127056679657e+00 +9.1047984200900955e-01 +-2.7836604710612223e+00 +-1.6647454050625340e-01 +5.8657011997714936e-01 +-3.5729703429702853e+00 +-4.0979172911028955e-01 +3.9286860410031527e-01 +-3.9093126007538839e+00 +-7.5315486953477451e-01 +3.0185997621808491e-01 +-2.5687962482656261e+00 +-1.2390040303351701e+00 +1.8459742463453255e-01 +-2.2500791845676233e+00 +-1.2390040303351701e+00 +1.8459742463453255e-01 +-2.2500791845676233e+00 +-8.9626512200274633e-01 +1.5060740383228730e-01 +-2.4252658417117008e+00 +-4.4651619444613933e-01 +2.8586075568119723e-01 +-4.0939273659632445e+00 +-1.0373659962427293e+00 +3.8488647234610579e-01 +-2.2888053915185318e+00 +-7.4922900644971691e-01 +6.0793323488497208e-01 +-2.5011955479268786e+00 +-1.2053904046255219e+00 +1.7273390104865810e-01 +-2.2307208875744271e+00 +-4.6644581789378908e-01 +3.5275036851110564e-01 +-4.1124376339099653e+00 +-5.3263147354185958e-01 +4.1108805901500090e-01 +-4.2083148470899401e+00 +-4.9855844626705137e-01 +4.9087657697029846e-01 +-4.1315351796979387e+00 +-8.8684371773806558e-01 +4.5588241014457992e-01 +-2.3669433016457053e+00 +-1.2731281970898378e+00 +4.8543348154459370e-01 +-2.2107655134106725e+00 +-4.2941749783880645e-01 +2.8615461648205792e-01 +-3.9742622061311188e+00 +-1.2577848765542718e+00 +3.1359327946634091e-01 +-2.2388650747660233e+00 +-1.9563415912913171e-01 +3.7969031745312304e-01 +-3.4925475610126080e+00 +-5.4513256145678235e-01 +4.9397178344213866e-01 +-4.2430317001886380e+00 +-5.4513256145678235e-01 +4.9397178344213866e-01 +-4.2430317001886380e+00 +-5.0339766272603104e-01 +4.9682861862449235e-01 +-4.1460550519308557e+00 +-5.4602899026459129e-01 +6.2439118321151144e-01 +-4.3595086314167864e+00 +-2.2666471625296850e-01 +6.4789424941461993e-01 +-3.6480759871854302e+00 +-1.2368669970153778e+00 +5.1039795348306216e-01 +-2.2123813536245653e+00 +-1.4161616627233482e+00 +5.4091997946155412e-01 +-2.2200019772416444e+00 +-1.0797276686446264e+00 +7.3581661818805277e-01 +-2.3254054074541775e+00 +-1.2027438392984142e+00 +6.1139824668636905e-02 +-2.2418603491961209e+00 +-7.4152600867133478e-01 +3.5569302090532673e-01 +-2.6048335032847860e+00 +-4.9805582583794006e-01 +5.3546627252963286e-01 +-4.1739818688367389e+00 +-4.5675628520461559e-01 +5.3933271859673970e-01 +-4.0883357445703687e+00 +-1.9992084343661659e-01 +6.8990009972631505e-01 +-3.7449344733089860e+00 +-7.0723019794140352e-01 +1.9452573376559085e-01 +-2.7704947064166898e+00 +1.2698846462984759e+00 +1.8464485697919372e-01 +-2.2461342412473249e+00 +-5.6964322003818446e-01 +4.0802683635399500e-01 +-4.3336473389867658e+00 +-2.0319485003003801e-01 +3.6164928771092075e-01 +-3.3809472967693348e+00 +-1.1408119368517912e-01 +4.1216862480153210e-01 +-3.3958245808703835e+00 +-3.8598427173147459e-01 +5.4081152226535389e-01 +-3.8905629094405105e+00 +-7.0909816670469694e-01 +4.5792081331430856e-01 +-2.6175072095779002e+00 +-9.0479955133109424e-01 +4.9144208209978774e-01 +-2.3244151999113902e+00 +-1.0502502032131963e-01 +3.0683564311211203e-01 +-7.1903806235169521e-01 +-1.1436972959472749e+00 +5.4300643397304038e-01 +-2.2265530446234987e+00 +-7.2967155912275317e-01 +6.1281302965101792e-01 +-2.5359265245269427e+00 +-1.0400012457923002e+00 +5.8475664052163090e-01 +-2.2291619192068022e+00 +-7.8418646643072354e-01 +6.2317818586710771e-01 +-2.4328002326977933e+00 +-7.4465169270056408e-01 +8.0201464672511780e-01 +-2.7619761017582416e+00 +-1.2279051625069428e+00 +5.5031847436317276e-02 +-2.2478751389113509e+00 +-4.8051628565620064e-01 +2.8750549368131051e-01 +-4.2094586807399201e+00 +-3.9912553636519249e-01 +3.4710769307796074e-01 +-3.9619490090294223e+00 +-5.3931195160855305e-01 +4.2296656121607928e-01 +-4.2296150186821571e+00 +-1.1461686630605006e-01 +3.6365413398295454e-01 +-3.2267500363950017e+00 +-5.7719724644798442e-01 +4.7344924355016521e-01 +-4.3106341475202932e+00 +-3.2445911804909378e-01 +4.6593320126895232e-01 +-3.7454350823523819e+00 +-3.9908264636496976e-01 +5.2736270380172801e-01 +-3.9009696037886097e+00 +-7.7564861677056052e-01 +4.8040924017670461e-01 +-2.4743015699316437e+00 +-7.3501035833951278e-01 +6.1704001803889119e-01 +-2.5315355788774947e+00 +-9.1943117060057400e-01 +6.1169204176185665e-01 +-2.3026993547965375e+00 +-8.5839545464538181e-01 +1.8602039189875466e-01 +-2.4443932355788203e+00 +-1.1337512028606032e-01 +2.8251984337563951e-01 +-3.3190628566658633e+00 +-7.3008089748770943e-01 +2.7168205524432448e-01 +-2.6566639069467390e+00 +-5.4601739530043292e-01 +4.3346989224370192e-01 +-4.2814087169955553e+00 +-5.4601739530043292e-01 +4.3346989224370192e-01 +-4.2814087169955553e+00 +-7.1274395305347349e-01 +3.6364841886906940e-01 +-2.6626690312007448e+00 +-4.5433403954952012e-01 +4.8005983286347464e-01 +-4.0077916320371090e+00 +-4.3296577661848379e-01 +5.2986201213388939e-01 +-4.0280093954138056e+00 +-8.8140204039051617e-01 +4.0945750034787598e-01 +-2.3729257219688327e+00 +-7.2659634891485303e-01 +4.5383685225436338e-01 +-2.5994973414772664e+00 +-4.7951313586775943e-02 +5.4278610790572701e-01 +-3.5246430028510876e+00 +-6.4072747080932224e-01 +5.3336564655061247e-01 +-2.8349632834664926e+00 +-6.4352753263851803e-01 +5.4959802094670174e-01 +-2.8402410847374542e+00 +-1.1977831907850614e-01 +6.4651693680268874e-01 +-3.6506245109813342e+00 +-7.8308981156290247e-01 +5.7149573447591295e-01 +-2.4437131889555355e+00 +-8.5391310636003637e-01 +5.9218204926638718e-01 +-2.3397056175396305e+00 +-9.6077373891242379e-01 +6.7381393823833080e-01 +-2.2589610246571445e+00 +1.3520301086333051e+00 +9.7939486818967997e-02 +-1.0995760820307556e+00 +1.3520301086333051e+00 +9.7939486818967997e-02 +-1.0995760820307556e+00 +1.3608694295720631e+00 +2.6390964524150645e-01 +-1.2115824959997155e+00 +1.3494540981017940e+00 +1.8579638900409129e-01 +-1.2438710122112904e+00 +1.3584254954943684e+00 +2.8234283037602209e-01 +-1.2487340969737086e+00 +1.3672745899948764e+00 +1.7961236963111024e-01 +-1.2280811494933350e+00 +1.3799513274778257e+00 +2.6433791641428656e-01 +-1.2846951402008253e+00 +1.3993966691210966e+00 +1.1870026791009294e-01 +-2.2921471208214870e+00 +1.3663134898527745e+00 +1.2840634517910698e-01 +-1.2551955025135086e+00 +1.3821276680590813e+00 +1.3554688240136697e-01 +-1.2785408882422571e+00 +1.3765368450885720e+00 +1.4194611121715242e-01 +-1.0255325181075734e+00 +1.3730606178799440e+00 +1.6612851651651639e-01 +-1.0278283513861886e+00 +1.3547493627470573e+00 +3.0860972809990189e-01 +-1.0940071357435170e+00 +1.9684150407287264e+00 +4.7340085131293191e-01 +-3.0374321027161209e+00 +1.3554047775747542e+00 +2.4733655727212735e-02 +-1.2418592384573237e+00 +1.4449087938686587e+00 +6.6910580880812406e-02 +-2.2650186522715172e+00 +1.3666285214294398e+00 +1.2996945114843414e-01 +-1.1789202748852188e+00 +1.3625819207799497e+00 +1.9793614597072148e-01 +-1.2585554172481792e+00 +1.3505770058759106e+00 +2.4056577210737817e-01 +-1.0815172858193811e+00 +1.3819337469007502e+00 +2.9212723874628110e-01 +-1.2696490835618846e+00 +1.3819337469007502e+00 +2.9212723874628110e-01 +-1.2696490835618846e+00 +1.3621723624853801e+00 +-1.0155519166594811e-02 +-1.0836910418950689e+00 +1.3627485976048994e+00 +3.0317998423611024e-02 +-1.1179389634005743e+00 +1.3952875064932131e+00 +1.8364499221075217e-01 +-2.2911631920635984e+00 +1.3658772820394181e+00 +1.8344037489758655e-01 +-2.3027508441823374e+00 +1.9938908750024285e+00 +2.2316836715096219e-01 +-2.6111362426454234e+00 +1.3621615548005448e+00 +2.0773256637161253e-01 +-1.1135913468876339e+00 +1.3760921245456841e+00 +2.1480460206711877e-01 +-1.0838186163837344e+00 +1.3592976217148858e+00 +2.2396613463026471e-01 +-1.2038181716799814e+00 +1.1148266994178870e+00 +2.4118530849442427e-01 +-1.0356023297530004e+00 +1.3821015333689359e+00 +3.0059538148455384e-01 +-1.2683310032342381e+00 +1.3643357854881613e+00 +3.6823487809114702e-01 +-1.1154256877926629e+00 +1.3643357854881613e+00 +3.6823487809114702e-01 +-1.1154256877926629e+00 +1.3973555358063605e+00 +4.0548761385316895e-01 +-1.2289962707283895e+00 +1.3949524835016103e+00 +4.0523871324622335e-01 +-1.1719259132224220e+00 +1.3572133216984070e+00 +-3.4577117937369700e-02 +-1.2098902835805678e+00 +1.3624514258725189e+00 +-2.2616972332602629e-02 +-1.0696791687722043e+00 +1.4389482375189033e+00 +-2.4274863341753959e-02 +-2.2736546976830612e+00 +1.4170406651025718e+00 +-2.3892818926205078e-02 +-2.2759557868465312e+00 +1.4028822002464725e+00 +2.8563648791824128e-02 +-1.0130772685751765e+00 +1.3991132009793839e+00 +4.8446131797811487e-02 +-1.0291717222302168e+00 +1.3576435350666736e+00 +5.6479734395740784e-02 +-1.1435377573093626e+00 +1.3598739138847167e+00 +6.6530718348311355e-02 +-1.1805212955667101e+00 +1.3620783532875405e+00 +1.8872246260195780e-01 +-1.2008498514733337e+00 +1.3774353532704890e+00 +-3.0176614218062805e-02 +-1.0844181638250570e+00 +1.4594699889538243e+00 +-2.1309568910198858e-02 +-2.2228647885516186e+00 +1.3742942296995191e+00 +3.5296314078876317e-02 +-1.0123623407217650e+00 +1.3713061213129036e+00 +4.1312134246819482e-02 +-1.1006427156686853e+00 +2.4928026890570822e+00 +3.6460144638952377e-02 +-2.3099994928978331e+00 +1.3726358428610181e+00 +1.0005610018776466e-01 +-2.3557001133830844e+00 +1.3950885241685340e+00 +1.4130466297792807e-01 +-1.0316245676186568e+00 +1.3473815706046000e+00 +1.7471185114308529e-01 +-1.1459801972632624e+00 +1.3811186423206916e+00 +1.9123601223332756e-01 +-2.3211907634879783e+00 +1.3786172772889536e+00 +1.9070349747835635e-01 +-2.3187136331688842e+00 +1.3819717358605723e+00 +2.2318722443283245e-01 +-1.0578577430509717e+00 +1.3539909551673888e+00 +2.4191914907387849e-01 +-1.1774214395278881e+00 +1.3578064555466069e+00 +2.5350617141026693e-01 +-1.1525281624504755e+00 +1.3634932462502625e+00 +3.1334910173519459e-01 +-1.2551740881063609e+00 +1.3576196801720930e+00 +3.1625780193321229e-01 +-1.1841286795653307e+00 +4.0752057492099096e+00 +6.1769190492031201e-01 +-3.0755827098820205e+00 +4.0517220316907601e+00 +6.1707907979377530e-01 +-3.0818733879135816e+00 +2.4979205642790339e+00 +3.6645432048243214e-02 +-2.3017262338302218e+00 +1.3902199231171117e+00 +8.5732761743755964e-02 +-1.0081068977310175e+00 +1.4019731935635442e+00 +9.4488235945969876e-02 +-1.0216286316750505e+00 +1.3491856575637122e+00 +1.4490900164264070e-01 +-1.1303084164700119e+00 +1.3818978877854444e+00 +2.2164081302259867e-01 +-1.0232937632753312e+00 +1.3594534959672639e+00 +2.2931159978694279e-01 +-1.1237847956179188e+00 +1.3665524774591389e+00 +2.2990262192930350e-01 +-1.0985024356897708e+00 +1.3639859093336482e+00 +2.3527030472535765e-01 +-1.1051151711926734e+00 +2.2407819364445842e+00 +5.3344915776269619e-01 +-3.2142430337483052e+00 +1.3704821627988419e+00 +6.0420799631594975e-02 +-1.1678638930501661e+00 +2.5072383458777598e+00 +2.3264522917238789e-01 +-2.3294133820665244e+00 +1.8870096572642088e+00 +5.4256126474692168e-01 +-3.1109157256686668e+00 +-4.0293219749836723e-01 +2.9001798329494261e-01 +-3.8793900522827331e+00 diff --git a/fuse_constraints/test/test_bal_problem.cpp b/fuse_constraints/test/test_bal_problem.cpp new file mode 100644 index 000000000..5949b933c --- /dev/null +++ b/fuse_constraints/test/test_bal_problem.cpp @@ -0,0 +1,500 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Dec 12 2023 + * + * Copyright (c) 2023 Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +using fuse_constraints::ReprojectionErrorSnavellyConstraint; +using fuse_variables::Orientation3DStamped; +using fuse_variables::PinholeCameraSimple; +using fuse_variables::Point3DFixedLandmark; +using fuse_variables::Point3DLandmark; +using fuse_variables::Position3DStamped; + +#ifndef BAL_PROBLEM_H +#define FUSE_CONSTRAINTS_REPROJECTION_ERROR_CONSTRAINT_H + +// BALProblem adapted from: +// https://ceres-solver.googlesource.com/ceres-solver/+/master/examples/simple_bundle_adjuster.cc +class BALProblem +{ +public: + BALProblem() + { + } + ~BALProblem() + { + delete[] point_index_; + delete[] camera_index_; + delete[] observations_; + delete[] parameters_; + } + int num_observations() const + { + return num_observations_; + } + const double* observations() const + { + return observations_; + } + double* mutable_cameras() + { + return parameters_; + } + double* mutable_points() + { + return parameters_ + 10 * num_cameras_; + } + double* mutable_camera_for_observation(int i) + { + return mutable_cameras() + camera_index_[i] * 10; + } + double* mutable_point_for_observation(int i) + { + return mutable_points() + point_index_[i] * 3; + } + int camera_for_observation(int i) + { + return camera_index_[i]; + } + int point_for_observation(int i) + { + return point_index_[i]; + } + double* camera(int i) + { + return mutable_cameras() + i * 10; + } + double* points(int i) + { + return mutable_points() + i * 3; + } + + bool LoadFile(const char* filename) + { + FILE* fptr = fopen(filename, "r"); + if (fptr == nullptr) + { + return false; + }; + FscanfOrDie(fptr, "%d", &num_cameras_); + FscanfOrDie(fptr, "%d", &num_points_); + FscanfOrDie(fptr, "%d", &num_observations_); + point_index_ = new int[num_observations_]; + camera_index_ = new int[num_observations_]; + observations_ = new double[2 * num_observations_]; + num_parameters_ = 9 * num_cameras_ + 3 * num_points_; + parameters_ = new double[num_parameters_]; + for (int i = 0; i < num_observations_; ++i) + { + FscanfOrDie(fptr, "%d", camera_index_ + i); + FscanfOrDie(fptr, "%d", point_index_ + i); + for (int j = 0; j < 2; ++j) + { + FscanfOrDie(fptr, "%lf", observations_ + 2 * i + j); + } + } + + for (int i = 0; i < num_parameters_; ++i) + { + FscanfOrDie(fptr, "%lf", parameters_ + i); + } + + { + // Switch the angle-axis rotations to quaternions. + num_parameters_ = 10 * num_cameras_ + 3 * num_points_; + auto* quaternion_parameters = new double[num_parameters_]; + double* original_cursor = parameters_; + double* quaternion_cursor = quaternion_parameters; + for (int i = 0; i < num_cameras_; ++i) + { + ceres::AngleAxisToQuaternion(original_cursor, quaternion_cursor); + quaternion_cursor += 4; + original_cursor += 3; + for (int j = 4; j < 10; ++j) + { + *quaternion_cursor++ = *original_cursor++; + } + } + // Copy the rest of the points. + for (int i = 0; i < 3 * num_points_; ++i) + { + *quaternion_cursor++ = *original_cursor++; + } + // Swap in the quaternion parameters. + delete[] parameters_; + parameters_ = quaternion_parameters; + } + + return true; + } + + int num_cameras() + { + return num_cameras_; + } + + int num_points() + { + return num_points_; + } + +private: + template + void FscanfOrDie(FILE* fptr, const char* format, T* value) + { + int num_scanned = fscanf(fptr, format, value); + if (num_scanned != 1) + { + LOG(FATAL) << "Invalid UW data file."; + } + } + int num_cameras_; + int num_points_; + int num_observations_; + int num_parameters_; + int* point_index_; + int* camera_index_; + double* observations_; + double* parameters_; + bool use_quaternions_; +}; +#endif + +// CeresSnavellyReprojectionErrorWithQuaternion adapted from: +// https://ceres-solver.googlesource.com/ceres-solver/+/master/examples/snavely_reprojection_error.h +// Templated pinhole camera model for used with Ceres. The camera is +// parameterized using 9 parameters: 3 for rotation, 3 for translation, 1 for +// focal length and 2 for radial distortion. The principal point is not modeled +// (i.e. it is assumed be located at the image center). +struct SnavelyReprojectionErrorWithQuaternions +{ + // (u, v): the position of the observation with respect to the image + // center point. + SnavelyReprojectionErrorWithQuaternions(double observed_x, double observed_y) + : observed_x(observed_x), observed_y(observed_y) + { + } + template + bool operator()(const T* const camera, const T* const point, T* residuals) const + { + // camera[0,1,2,3] is are the rotation of the camera as a quaternion. + // + // We use QuaternionRotatePoint as it does not assume that the + // quaternion is normalized, since one of the ways to run the + // bundle adjuster is to let Ceres optimize all 4 quaternion + // parameters without using a Quaternion manifold. + T p[3]; + ceres::QuaternionRotatePoint(camera, point, p); + p[0] += camera[4]; + p[1] += camera[5]; + p[2] += camera[6]; + // Compute the center of distortion. The sign change comes from + // the camera model that Noah Snavely's Bundler assumes, whereby + // the camera coordinate system has a negative z axis. + const T xp = -p[0] / p[2]; + const T yp = -p[1] / p[2]; + // Apply second and fourth order radial distortion. + const T& l1 = camera[8]; + const T& l2 = camera[9]; + const T r2 = xp * xp + yp * yp; + const T distortion = 1.0 + r2 * (l1 + l2 * r2); + // Compute final projected point position. + const T& focal = camera[7]; + const T predicted_x = focal * distortion * xp; + const T predicted_y = focal * distortion * yp; + + residuals[0] = predicted_x - observed_x; + residuals[1] = predicted_y - observed_y; + return true; + } + + static ceres::CostFunction* Create(const double observed_x, const double observed_y) + { + return (new ceres::AutoDiffCostFunction( + new SnavelyReprojectionErrorWithQuaternions(observed_x, observed_y))); + } + double observed_x; + double observed_y; +}; + +TEST(ReprojectionErrorSnavellyConstraint, Constructor) +{ + // Construct a constraint just to make sure it compiles. + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Point3DLandmark point(0); + PinholeCameraSimple calibration_variable(0); + + fuse_core::Vector2d mean; + mean << 320.0, 240.0; // Centre of a 640x480 camera + + // Assume Half a pixel Variance + fuse_core::Matrix2d cov; + cov << 0.5, 0.0, // NOLINT + 0.0, 0.5; // NOLINT + + EXPECT_NO_THROW(ReprojectionErrorSnavellyConstraint constraint("test", position_variable, orientation_variable, + calibration_variable, mean, cov)); +} + +TEST(ReprojectionErrorSnavellyConstraint, Covariance) +{ + // Verify the covariance <--> sqrt information conversions are correct + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("mo")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("mo")); + Point3DLandmark point(0); + PinholeCameraSimple calibration_variable(0); + + fuse_core::Vector2d mean; + mean << 320.0, 240.0; // Centre of a 640x480 camera + + // Assume Half a pixel Variance + fuse_core::Matrix2d cov; + cov << 0.5, 0.0, // NOLINT + 0.0, 0.5; // NOLINT + + ReprojectionErrorSnavellyConstraint constraint("test", position_variable, orientation_variable, calibration_variable, + mean, cov); + + // Define the expected matrices (used Octave to compute sqrt_info: 'chol(inv(A))') + fuse_core::Matrix2d expected_sqrt_info; + expected_sqrt_info << 1.414213562373095, 0, // NOLINT + 0, 1.414213562373095; // NOLINT + fuse_core::Matrix2d expected_cov = cov; + + // Compare + EXPECT_MATRIX_NEAR(expected_cov, constraint.covariance(), 1.0e-9); + EXPECT_MATRIX_NEAR(expected_sqrt_info, constraint.sqrtInformation(), 1.0e-9); +} + +TEST(ReprojectionErrorSnavellyConstraint, BAL) +{ + std::string filename = "problem-21-11315-pre.txt"; + BALProblem bal_problem_ceres; + if (!bal_problem_ceres.LoadFile(filename.c_str())) + { + std::cerr << "ERROR: unable to open file " << filename << "\n"; + throw; + } + + // Use Ceres Standard + const double* observations_ceres = bal_problem_ceres.observations(); + ceres::Problem problem_ceres; + for (int i = 0; i < bal_problem_ceres.num_observations(); ++i) + { + ceres::CostFunction* cost_function = + SnavelyReprojectionErrorWithQuaternions::Create(observations_ceres[2 * i + 0], observations_ceres[2 * i + 1]); + problem_ceres.AddResidualBlock(cost_function, nullptr /* squared loss */, + bal_problem_ceres.mutable_camera_for_observation(i), + bal_problem_ceres.mutable_point_for_observation(i)); + } + ceres::Solver::Options options_ceres; + options_ceres.linear_solver_type = ceres::DENSE_SCHUR; + ceres::Solver::Summary summary_ceres; + ceres::Solve(options_ceres, &problem_ceres, &summary_ceres); + + BALProblem bal_problem; + if (!bal_problem.LoadFile(filename.c_str())) + { + std::cerr << "ERROR: unable to open file " << filename << "\n"; + throw; + } + + std::vector cams_p(bal_problem.num_cameras()); + std::vector cams_q(bal_problem.num_cameras()); + std::vector cams_k(bal_problem.num_cameras()); + for (int i = 0; i < bal_problem.num_cameras(); i++) + { + auto cam = bal_problem.camera(i); + + cams_q[i].w() = cam[0]; + cams_q[i].x() = cam[1]; + cams_q[i].y() = cam[2]; + cams_q[i].z() = cam[3]; + + cams_p[i].x() = cam[4]; + cams_p[i].y() = cam[5]; + cams_p[i].z() = cam[6]; + + cams_k[i].f() = cam[7]; + cams_k[i].r1() = cam[8]; + cams_k[i].r2() = cam[9]; + } + + std::vector pts(bal_problem.num_points()); + for (int i = 0; i < bal_problem.num_points(); i++) + { + auto pt = bal_problem.points(i); + pts[i].x() = pt[0]; + pts[i].y() = pt[1]; + pts[i].z() = pt[2]; + } + + ceres::Problem problem; + const double* observations = bal_problem.observations(); + for (int i = 0; i < bal_problem.num_observations(); ++i) + { + int c = bal_problem.camera_for_observation(i); + cams_q[c]; + cams_p[c]; + cams_k[c]; + + int p = bal_problem.point_for_observation(i); + pts[p]; + + // Create an observation + fuse_core::Vector2d mean; + mean << observations[2 * i + 0], observations[2 * i + 1]; + + // Define Observation Covariance + fuse_core::Matrix2d cov; + cov << 1e-5, 0.0, // NOLINT + 0.0, 1e-5; // NOLINT + + auto constraint = + ReprojectionErrorSnavellyConstraint::make_shared("test", cams_p[c], cams_q[c], cams_k[c], mean, cov); + + problem.AddParameterBlock(pts[p].data(), pts[p].size(), pts[p].localParameterization()); + + std::vector parameter_blocks; + parameter_blocks.push_back(cams_p[c].data()); + parameter_blocks.push_back(cams_q[c].data()); + parameter_blocks.push_back(cams_k[c].data()); + parameter_blocks.push_back(pts[p].data()); + + problem.AddResidualBlock(constraint->costFunction(), constraint->lossFunction(), parameter_blocks); + } + + ceres::Solver::Options options; + options.linear_solver_type = ceres::DENSE_SCHUR; + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + + for (int i = 0; i < bal_problem.num_cameras(); i++) + { + auto cam = bal_problem_ceres.camera(i); + + EXPECT_NEAR(cams_q[i].w(), cam[0], 1e-2); + EXPECT_NEAR(cams_q[i].x(), cam[1], 1e-2); + EXPECT_NEAR(cams_q[i].y(), cam[2], 1e-2); + EXPECT_NEAR(cams_q[i].z(), cam[3], 1e-2); + + EXPECT_NEAR(cams_p[i].x(), cam[4], 1e-2); + EXPECT_NEAR(cams_p[i].y(), cam[5], 1e-2); + EXPECT_NEAR(cams_p[i].z(), cam[6], 1e-2); + + EXPECT_NEAR(cams_k[i].f(), cam[7], 1e-2); + EXPECT_NEAR(cams_k[i].r1(), cam[8], 1e-2); + EXPECT_NEAR(cams_k[i].r2(), cam[9], 1e-2); + } + + for (int i = 0; i < bal_problem.num_points(); i++) + { + auto pt = bal_problem_ceres.points(i); + EXPECT_NEAR(pts[i].x(), pt[0], 1e-2); + EXPECT_NEAR(pts[i].y(), pt[1], 1e-2); + EXPECT_NEAR(pts[i].z(), pt[2], 1e-2); + } +} + +TEST(ReprojectionErrorSnavellyConstraint, Serialization) +{ + // Construct a constraint + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + + PinholeCameraSimple calibration_variable(0); + calibration_variable.f() = 640; + calibration_variable.r1() = 0.1; + calibration_variable.r2() = 0.1; + + fuse_core::Vector2d mean; + mean << 261.71822455, 168.60442225; + + // Generated PD matrix using Octave: R = rand(6, 6); A = R * R' (use format long g to get the required precision) + fuse_core::Matrix2d cov; + cov << 0.5, 0.0, // NOLINT + 0.5, 0.5; // NOLINT + + ReprojectionErrorSnavellyConstraint expected("test", position_variable, orientation_variable, calibration_variable, + mean, cov); + + // Serialize the constraint into an archive + std::stringstream stream; + { + fuse_core::TextOutputArchive archive(stream); + expected.serialize(archive); + } + + // Deserialize a new constraint from that same stream + ReprojectionErrorSnavellyConstraint actual; + { + fuse_core::TextInputArchive archive(stream); + actual.deserialize(archive); + } + + // Compare + EXPECT_EQ(expected.uuid(), actual.uuid()); + EXPECT_EQ(expected.variables(), actual.variables()); + EXPECT_MATRIX_EQ(expected.mean(), actual.mean()); + EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation()); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/fuse_constraints/test/test_fixed_3d_landmark_constraint.py b/fuse_constraints/test/test_fixed_3d_landmark_constraint.py index fd0f2b189..b7a18fe3f 100644 --- a/fuse_constraints/test/test_fixed_3d_landmark_constraint.py +++ b/fuse_constraints/test/test_fixed_3d_landmark_constraint.py @@ -19,6 +19,13 @@ def __init__(self,): self.cx = 310.29060457226840 self.cy = 237.80861559081677 + # Dist Parameters + self.k1 = 0.13281739520782995 + self.k2 = -0.17255676937880005 + self.p1 = -0.0036963860577237523 + self.p2 = -0.00884659526000406 + self.k3 = 0.0 + # Make Matrix self.K = np.eye(4) self.K[0,0] = self.fx @@ -68,8 +75,25 @@ def project_points(self, camPos, pts3d): x[:,1]/=x[:,2] x[:,2]/=x[:,2] return x + + def project_points_snavelly(self, camPos, pts3d): + Ks = np.eye(4) + Ks[0,0] = self.fx + Ks[1,1] = self.fx + Ks[0,2] = 0 + Ks[1,2] = 0 + + x = np.matmul(camPos, pts3d.transpose()).transpose() + x[:,0]/=-x[:,2] + x[:,1]/=-x[:,2] + x[:,2]/=-x[:,2] + + r2 = x*x + d = 1.0 + r2*(self.k1+self.k2*r2) + x = Ks[0,0]*d*x + return x - def plot(self, pts2d, pts3d): + def plot(self, pts2d, pts3d, is_snavelly=False): import matplotlib.pyplot as plt @@ -79,9 +103,14 @@ def plot(self, pts2d, pts3d): ax.scatter(pts3d[:,0], pts3d[:,1], pts3d[:,2]) ax = fig.add_subplot(1,2,2) - ax.scatter(pts2d[:,0], pts2d[:,1], pts2d[:,2]) - ax.set_xlim([0, self.w]) - ax.set_ylim([0, self.h]) + ax.scatter(pts2d[:,0], pts2d[:,1]) + if is_snavelly: + ax.set_xlim([-self.w/2, self.w/2]) + ax.set_ylim([-self.h/2, self.h/2]) + else: + ax.set_xlim([0, self.w]) + ax.set_ylim([0, self.h]) + plt.show() def project_poses(self, pts3d): @@ -109,6 +138,16 @@ def Optimization(self): self.print_points(x, X) self.plot(x, X) + def OptimizationSnavelly(self): + print("Points for OptimizationSnavelly") + print(f"f = {self.fx}") + print(f"k1 = {self.k1}") + print(f"k2 = {self.k2}") + X = np.matmul(self.T, self.X.transpose()).transpose() + x = self.project_points_snavelly(np.eye(4), X) + self.print_points(x, X) + self.plot(x, X, True) + def OptimizationScaledMarker(self): print("Points for OptimizationScaledMarker") print(f"fx = {self.fx}") @@ -186,7 +225,8 @@ def MultiViewOptimization(self): if __name__ == '__main__': tests = PinholeCameraProjection() - tests.Optimization() - tests.OptimizationScaledMarker() - tests.OptimizationPoints() - tests.MultiViewOptimization() + # tests.Optimization() + tests.OptimizationSnavelly() + # tests.OptimizationScaledMarker() + # tests.OptimizationPoints() + # tests.MultiViewOptimization() diff --git a/fuse_constraints/test/test_fixed_3d_landmark_simple_covariance_constraint.cpp b/fuse_constraints/test/test_fixed_3d_landmark_simple_covariance_constraint.cpp new file mode 100644 index 000000000..07138067f --- /dev/null +++ b/fuse_constraints/test/test_fixed_3d_landmark_simple_covariance_constraint.cpp @@ -0,0 +1,631 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Fri Nov 17 2023 + * + * Copyright (c) 2023 Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +using fuse_constraints::Fixed3DLandmarkSimpleCovarianceConstraint; +using fuse_variables::Orientation3DStamped; +using fuse_variables::PinholeCameraFixed; +using fuse_variables::Position3DStamped; + +TEST(Fixed3DLandmarkSimpleCovarianceConstraint, Constructor) +{ + // Construct a constraint just to make sure it compiles. + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + PinholeCameraFixed calibration_variable(0); + + double marker_size = 1.0; + + fuse_core::Vector7d mean; + mean << 1.0, 2.0, 3.0, 1.0, 0.0, 0.0, 0.0; + + // Generated PD matrix using Octave: R = rand(6, 6); A = R * R' (use format long g to get the required precision) + fuse_core::Matrix2d cov; + cov << 0.25, 0.0, // NOLINT + 0.0, 0.25; // NOLINT + + // 2D observations (arbitrary) + Eigen::Matrix obs; + obs << 320, 240, 320, 240, 320, 240, 320, 240; + + EXPECT_NO_THROW(Fixed3DLandmarkSimpleCovarianceConstraint constraint( + "test", position_variable, orientation_variable, calibration_variable, marker_size, obs, mean, cov)); +} + +TEST(Fixed3DLandmarkSimpleCovarianceConstraint, Covariance) +{ + // Verify the covariance <--> sqrt information conversions are correct + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("mo")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("mo")); + PinholeCameraFixed calibration_variable(0); + + double marker_size = 1.0; + + fuse_core::Vector7d mean; + mean << 1.0, 2.0, 3.0, 1.0, 0.0, 0.0, 0.0; + + // Generated PD matrix using Octiave: R = rand(6, 6); A = R * R' (use format long g to get the required precision) + fuse_core::Matrix2d cov; + cov << 0.25, 0.0, // NOLINT + 0.0, 0.25; // NOLINT + + // 2D observations (arbitrary) + Eigen::Matrix obs; + obs << 320, 240, 320, 240, 320, 240, 320, 240; + + Fixed3DLandmarkSimpleCovarianceConstraint constraint("test", position_variable, orientation_variable, + calibration_variable, marker_size, obs, mean, cov); + + // Define the expected matrices (used Octave to compute sqrt_info: 'chol(inv(A))') + fuse_core::Matrix2d expected_sqrt_info; + expected_sqrt_info << 2.0, 0.0, // NOLINT + 0.0, 2.0; // NOLINT + fuse_core::Matrix2d expected_cov = cov; + + // Compare + EXPECT_MATRIX_NEAR(expected_cov, constraint.covariance(), 1.0e-9); + EXPECT_MATRIX_NEAR(expected_sqrt_info, constraint.sqrtInformation(), 1.0e-9); +} + +TEST(Fixed3DLandmarkSimpleCovarianceConstraint, Optimization) +{ + // Optimize a single pose and single constraint, verify the expected value and covariance are generated. + // Create the variables + auto position_variable = Position3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + position_variable->x() = 1.5; + position_variable->y() = -3.0; + position_variable->z() = 10.0; + + auto orientation_variable = Orientation3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + orientation_variable->w() = 0.952; + orientation_variable->x() = 0.038; + orientation_variable->y() = -0.189; + orientation_variable->z() = 0.239; + + auto calibration_variable = PinholeCameraFixed::make_shared(0); + calibration_variable->fx() = 638.34478759765620; + calibration_variable->fy() = 643.10717773437500; + calibration_variable->cx() = 310.29060457226840; + calibration_variable->cy() = 237.80861559081677; + + // Define Marker Size + double marker_size = 1.0; + + // Create an fixed position for the marker. + fuse_core::Vector7d mean; + mean << 0, 0, 10, 0.9238795, 0, -0.3826834, 0; + + // And observations... + Eigen::Matrix obs; + obs << 261.71822455, 168.60442225, // NOLINT + 261.71822455, 307.01280893, // NOLINT + 352.44745875, 177.74503448, // NOLINT + 352.44745875, 297.87219670; // NOLINT + + // Define Pose Covariance + fuse_core::Matrix2d cov; + cov << 0.25, 0.0, // NOLINT + 0.0, 0.25; // NOLINT + + auto constraint = Fixed3DLandmarkSimpleCovarianceConstraint::make_shared( + "test", *position_variable, *orientation_variable, *calibration_variable, marker_size, obs, mean, cov); + + // Build the problem + ceres::Problem::Options problem_options; + problem_options.loss_function_ownership = fuse_core::Loss::Ownership; + ceres::Problem problem(problem_options); + problem.AddParameterBlock(position_variable->data(), position_variable->size(), + position_variable->localParameterization()); + problem.AddParameterBlock(orientation_variable->data(), orientation_variable->size(), + orientation_variable->localParameterization()); + problem.AddParameterBlock(calibration_variable->data(), calibration_variable->size(), + calibration_variable->localParameterization()); + + std::vector parameter_blocks; + parameter_blocks.push_back(position_variable->data()); + parameter_blocks.push_back(orientation_variable->data()); + parameter_blocks.push_back(calibration_variable->data()); + + if (calibration_variable->holdConstant()) + { + problem.SetParameterBlockConstant(calibration_variable->data()); + } + + problem.AddResidualBlock(constraint->costFunction(), constraint->lossFunction(), parameter_blocks); + + // Run the solver + ceres::Solver::Options options; + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + + // Check + EXPECT_NEAR(0.0, position_variable->x(), 1.0e-5); + EXPECT_NEAR(0.0, position_variable->y(), 1.0e-5); + EXPECT_NEAR(0.0, position_variable->z(), 1.0e-5); + + EXPECT_NEAR(1.0, orientation_variable->w(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_variable->x(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_variable->y(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_variable->z(), 1.0e-3); + + EXPECT_NEAR(638.34478759765620, calibration_variable->fx(), 1.0e-3); + EXPECT_NEAR(643.10717773437500, calibration_variable->fy(), 1.0e-3); + EXPECT_NEAR(310.29060457226840, calibration_variable->cx(), 1.0e-3); + EXPECT_NEAR(237.80861559081677, calibration_variable->cy(), 1.0e-3); + + // // Compute the covariance + // std::vector > covariance_blocks; + // covariance_blocks.emplace_back(position_variable->data(), position_variable->data()); + // covariance_blocks.emplace_back(orientation_variable->data(), orientation_variable->data()); + // covariance_blocks.emplace_back(position_variable->data(), orientation_variable->data()); + + // ceres::Covariance::Options cov_options; + // ceres::Covariance covariance(cov_options); + // covariance.Compute(covariance_blocks, &problem); + // fuse_core::MatrixXd cov_pos_pos(position_variable->size(), position_variable->size()); + // covariance.GetCovarianceBlock(position_variable->data(), position_variable->data(), cov_pos_pos.data()); + + // fuse_core::MatrixXd cov_or_or(orientation_variable->localSize(), orientation_variable->localSize()); + // covariance.GetCovarianceBlockInTangentSpace( + // orientation_variable->data(), orientation_variable->data(), cov_or_or.data()); + + // fuse_core::MatrixXd cov_pos_or(position_variable->localSize(), orientation_variable->localSize()); + // covariance.GetCovarianceBlockInTangentSpace( + // position_variable->data(), orientation_variable->data(), cov_pos_or.data()); + + // // Assemble the full covariance from the covariance blocks + // fuse_core::Matrix2d actual_covariance; + // actual_covariance << cov_pos_pos, cov_pos_or, cov_pos_or.transpose(), cov_or_or; + + // // Define the expected covariance + // fuse_core::Matrix2d cov; + // cov << 0.25, 0.0, // NOLINT + // 0.0, 0.25; // NOLINT + + // EXPECT_MATRIX_NEAR(expected_covariance, actual_covariance, 1.0e-5); +} + +TEST(Fixed3DLandmarkSimpleCovarianceConstraint, OptimizationScaledMarker) +{ + // Optimize a single pose and single constraint, verify the expected value and covariance are generated. + // Create the variables + auto position_variable = Position3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + position_variable->x() = 1.5; + position_variable->y() = -3.0; + position_variable->z() = 10.0; + + auto orientation_variable = Orientation3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + orientation_variable->w() = 0.952; + orientation_variable->x() = 0.038; + orientation_variable->y() = -0.189; + orientation_variable->z() = 0.239; + + auto calibration_variable = PinholeCameraFixed::make_shared(0); + calibration_variable->fx() = 638.34478759765620; + calibration_variable->fy() = 643.10717773437500; + calibration_variable->cx() = 310.29060457226840; + calibration_variable->cy() = 237.80861559081677; + + // Define Marker Size + double marker_size = 0.25; + + // Create an fixed position for the marker. + fuse_core::Vector7d mean; + mean << 0, 0, 10, 0.9238795, 0, -0.3826834, 0; + + // And observations... + Eigen::Matrix obs; + obs << 298.8030834636202, 221.44160554498040, // NOLINT + 298.8030834636202, 254.17562563665314, // NOLINT + 321.3790354517349, 222.01021505859384, // NOLINT + 321.3790354517349, 253.60701612303970; // NOLINT + + // Define Pose Covariance + fuse_core::Matrix2d cov; + cov << 0.25, 0.0, // NOLINT + 0.0, 0.25; // NOLINT + + auto constraint = Fixed3DLandmarkSimpleCovarianceConstraint::make_shared( + "test", *position_variable, *orientation_variable, *calibration_variable, marker_size, obs, mean, cov); + + // Build the problem + ceres::Problem::Options problem_options; + problem_options.loss_function_ownership = fuse_core::Loss::Ownership; + ceres::Problem problem(problem_options); + problem.AddParameterBlock(position_variable->data(), position_variable->size(), + position_variable->localParameterization()); + problem.AddParameterBlock(orientation_variable->data(), orientation_variable->size(), + orientation_variable->localParameterization()); + problem.AddParameterBlock(calibration_variable->data(), calibration_variable->size(), + calibration_variable->localParameterization()); + + std::vector parameter_blocks; + parameter_blocks.push_back(position_variable->data()); + parameter_blocks.push_back(orientation_variable->data()); + parameter_blocks.push_back(calibration_variable->data()); + + if (calibration_variable->holdConstant()) + { + problem.SetParameterBlockConstant(calibration_variable->data()); + } + + problem.AddResidualBlock(constraint->costFunction(), constraint->lossFunction(), parameter_blocks); + + // Run the solver + ceres::Solver::Options options; + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + + // Check + EXPECT_NEAR(0.0, position_variable->x(), 1.0e-5); + EXPECT_NEAR(0.0, position_variable->y(), 1.0e-5); + EXPECT_NEAR(0.0, position_variable->z(), 1.0e-5); + + EXPECT_NEAR(1.0, orientation_variable->w(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_variable->x(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_variable->y(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_variable->z(), 1.0e-3); + + EXPECT_NEAR(638.34478759765620, calibration_variable->fx(), 1.0e-3); + EXPECT_NEAR(643.10717773437500, calibration_variable->fy(), 1.0e-3); + EXPECT_NEAR(310.29060457226840, calibration_variable->cx(), 1.0e-3); + EXPECT_NEAR(237.80861559081677, calibration_variable->cy(), 1.0e-3); +} + +TEST(Fixed3DLandmarkSimpleCovarianceConstraint, OptimizationPoints) +{ + // Optimize a single pose and single constraint, verify the expected value and covariance are generated. + // Create the variables + auto position_variable = Position3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + position_variable->x() = 1.5; + position_variable->y() = -3.0; + position_variable->z() = 10.0; + + auto orientation_variable = Orientation3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + orientation_variable->w() = 0.952; + orientation_variable->x() = 0.038; + orientation_variable->y() = -0.189; + orientation_variable->z() = 0.239; + + auto calibration_variable = PinholeCameraFixed::make_shared(0); + calibration_variable->fx() = 638.34478759765620; + calibration_variable->fy() = 643.10717773437500; + calibration_variable->cx() = 310.29060457226840; + calibration_variable->cy() = 237.80861559081677; + + // Create an fixed position for the marker. + fuse_core::Vector7d mean; + mean << 0, 0, 10, 0.9238795, 0, -0.3826834, 0; + + // Create the 3D points + Eigen::Matrix pts3d; + pts3d << -1.50, -1.5, 0.0, // NOLINT + -1.50, 1.5, 0.0, // NOLINT + 1.50, -1.5, 0.0, // NOLINT + 1.50, 1.5, 0.0, // NOLINT + 3.24, -1.5, 0.0, // NOLINT + 3.24, 1.5, 0.0, // NOLINT + 1.74, -1.5, 0.0, // NOLINT + 1.74, 1.5, 0.0; // NOLINT + + // And observations... + Eigen::Matrix obs; + obs << 234.55045762290558, 129.89675764784400, // NOLINT + 234.55045762290558, 345.72047353378950, // NOLINT + 371.50457352525080, 150.59313756704000, // NOLINT + 371.50457352525080, 325.02409361459354, // NOLINT + 429.27697088295537, 159.32364907215157, // NOLINT + 429.27697088295537, 316.29358210948200, // NOLINT + 380.22578098989925, 151.91107841060833, // NOLINT + 380.22578098989925, 323.70615277102520; // NOLINT + + // Define Pose Covariance + fuse_core::Matrix2d cov; + cov << 0.25, 0.0, // NOLINT + 0.0, 0.25; // NOLINT + + auto constraint = Fixed3DLandmarkSimpleCovarianceConstraint::make_shared( + "test", *position_variable, *orientation_variable, *calibration_variable, pts3d, obs, mean, cov); + + // Build the problem + ceres::Problem::Options problem_options; + problem_options.loss_function_ownership = fuse_core::Loss::Ownership; + ceres::Problem problem(problem_options); + problem.AddParameterBlock(position_variable->data(), position_variable->size(), + position_variable->localParameterization()); + problem.AddParameterBlock(orientation_variable->data(), orientation_variable->size(), + orientation_variable->localParameterization()); + problem.AddParameterBlock(calibration_variable->data(), calibration_variable->size(), + calibration_variable->localParameterization()); + + std::vector parameter_blocks; + parameter_blocks.push_back(position_variable->data()); + parameter_blocks.push_back(orientation_variable->data()); + parameter_blocks.push_back(calibration_variable->data()); + + if (calibration_variable->holdConstant()) + { + problem.SetParameterBlockConstant(calibration_variable->data()); + } + + problem.AddResidualBlock(constraint->costFunction(), constraint->lossFunction(), parameter_blocks); + + // Run the solver + ceres::Solver::Options options; + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + + // Check + EXPECT_NEAR(0.0, position_variable->x(), 1.0e-5); + EXPECT_NEAR(0.0, position_variable->y(), 1.0e-5); + EXPECT_NEAR(0.0, position_variable->z(), 1.0e-5); + + EXPECT_NEAR(1.0, orientation_variable->w(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_variable->x(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_variable->y(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_variable->z(), 1.0e-3); + + EXPECT_NEAR(638.34478759765620, calibration_variable->fx(), 1.0e-3); + EXPECT_NEAR(643.10717773437500, calibration_variable->fy(), 1.0e-3); + EXPECT_NEAR(310.29060457226840, calibration_variable->cx(), 1.0e-3); + EXPECT_NEAR(237.80861559081677, calibration_variable->cy(), 1.0e-3); +} + +TEST(Fixed3DLandmarkSimpleCovarianceConstraint, MultiViewOptimization) +{ + // Optimize a single pose and single constraint, verify the expected value and covariance are generated. + // Create the variables + + auto calibration_variable = PinholeCameraFixed::make_shared(0); + calibration_variable->fx() = 638.34478759765620; + calibration_variable->fy() = 643.10717773437500; + calibration_variable->cx() = 310.29060457226840; + calibration_variable->cy() = 237.80861559081677; + + // Define Marker Size + double marker_size = 1.0; + + // Build the problem + ceres::Problem::Options problem_options; + problem_options.loss_function_ownership = fuse_core::Loss::Ownership; + ceres::Problem problem(problem_options); + + // Create N Constraints + uint N = 5; + std::vector > obs(5); + + obs[0] << 124.33479102109460, 30.196035559968568, // NOLINT + 124.33479102109460, 168.60442224720070, // NOLINT + 233.20987206846505, 57.617872261057050, // NOLINT + 233.20987206846505, 177.74503448089686; // NOLINT + + obs[1] << 193.02650778349710, 99.400228903584630, // NOLINT + 193.02650778349710, 237.80861559081677, // NOLINT + 292.82866541025334, 117.68145337097695, // NOLINT + 292.82866541025334, 237.80861559081677; // NOLINT + + obs[2] << 373.42853736463960, 168.46718090279768, // NOLINT + 373.42853736463960, 307.15005027883580, // NOLINT + 466.82773058187524, 176.09986812497370, // NOLINT + 466.82773058187524, 299.51736305665980; // NOLINT + + obs[3] << 442.25647916056020, 237.80861559081674, // NOLINT + 442.25647916056020, 376.49148496685490, // NOLINT + 528.07950735845330, 237.80861559081677, // NOLINT + 528.07950735845330, 361.22611052250290; // NOLINT + + obs[4] << 511.08442095648064, 307.15005027883580, // NOLINT + 511.08442095648064, 445.83291965487400, // NOLINT + 589.33128413503120, 299.51736305665980, // NOLINT + 589.33128413503120, 422.93485798834600; // NOLINT + + std::vector position_vars(N); + std::vector orientation_vars(N); + + for (uint i = 0; i < N; i++) + { + position_vars[i] = Position3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + position_vars[i]->x() = 0.0; + position_vars[i]->y() = 0.0; + position_vars[i]->z() = 0.0; + + orientation_vars[i] = Orientation3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + orientation_vars[i]->w() = 0.952; + orientation_vars[i]->x() = 0.038; + orientation_vars[i]->y() = -0.189; + orientation_vars[i]->z() = 0.239; + + problem.AddParameterBlock(position_vars[i]->data(), position_vars[i]->size(), + position_vars[i]->localParameterization()); + problem.AddParameterBlock(orientation_vars[i]->data(), orientation_vars[i]->size(), + orientation_vars[i]->localParameterization()); + problem.AddParameterBlock(calibration_variable->data(), calibration_variable->size(), + calibration_variable->localParameterization()); + + std::vector parameter_blocks; + parameter_blocks.push_back(position_vars[i]->data()); + parameter_blocks.push_back(orientation_vars[i]->data()); + parameter_blocks.push_back(calibration_variable->data()); + + // Create an fixed position for the marker. + fuse_core::Vector7d mean; + mean << 0, 0, 10, 0.9238795, 0, -0.3826834, 0; + + fuse_core::Matrix2d cov; + cov << 0.25, 0.0, // NOLINT + 0.0, 0.25; // NOLINT + + auto constraint = Fixed3DLandmarkSimpleCovarianceConstraint::make_shared( + "test", *position_vars[i], *orientation_vars[i], *calibration_variable, marker_size, obs[i], mean, cov); + + problem.AddResidualBlock(constraint->costFunction(), constraint->lossFunction(), parameter_blocks); + } + + if (calibration_variable->holdConstant()) + { + problem.SetParameterBlockConstant(calibration_variable->data()); + } + + // Run the solver + ceres::Solver::Options options; + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + + // Check + EXPECT_NEAR(-2.0, position_vars[0]->x(), 1.0e-5); + EXPECT_NEAR(-2.0, position_vars[0]->y(), 1.0e-5); + EXPECT_NEAR(0.0, position_vars[0]->z(), 1.0e-5); + + EXPECT_NEAR(1.0, orientation_vars[0]->w(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[0]->x(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[0]->y(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[0]->z(), 1.0e-3); + + EXPECT_NEAR(-1.0, position_vars[1]->x(), 1.0e-5); + EXPECT_NEAR(-1.0, position_vars[1]->y(), 1.0e-5); + EXPECT_NEAR(0.0, position_vars[1]->z(), 1.0e-5); + + EXPECT_NEAR(1.0, orientation_vars[1]->w(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[1]->x(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[1]->y(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[1]->z(), 1.0e-3); + + EXPECT_NEAR(0.0, position_vars[2]->x(), 1.0e-5); + EXPECT_NEAR(0.0, position_vars[2]->y(), 1.0e-5); + EXPECT_NEAR(0.0, position_vars[2]->z(), 1.0e-5); + + EXPECT_NEAR(0.9961947, orientation_vars[2]->w(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[2]->x(), 1.0e-3); + EXPECT_NEAR(0.0871557, orientation_vars[2]->y(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[2]->z(), 1.0e-3); + + EXPECT_NEAR(1.0, position_vars[3]->x(), 1.0e-5); + EXPECT_NEAR(1.0, position_vars[3]->y(), 1.0e-5); + EXPECT_NEAR(0.0, position_vars[3]->z(), 1.0e-5); + + EXPECT_NEAR(0.9961947, orientation_vars[3]->w(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[3]->x(), 1.0e-3); + EXPECT_NEAR(0.0871557, orientation_vars[3]->y(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[3]->z(), 1.0e-3); + + EXPECT_NEAR(2.0, position_vars[4]->x(), 1.0e-5); + EXPECT_NEAR(2.0, position_vars[4]->y(), 1.0e-5); + EXPECT_NEAR(0.0, position_vars[4]->z(), 1.0e-5); + + EXPECT_NEAR(0.9961947, orientation_vars[4]->w(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[4]->x(), 1.0e-3); + EXPECT_NEAR(0.0871557, orientation_vars[4]->y(), 1.0e-3); + EXPECT_NEAR(0.0, orientation_vars[4]->z(), 1.0e-3); + + EXPECT_NEAR(638.34478759765620, calibration_variable->fx(), 1.0e-3); + EXPECT_NEAR(643.10717773437500, calibration_variable->fy(), 1.0e-3); + EXPECT_NEAR(310.29060457226840, calibration_variable->cx(), 1.0e-3); + EXPECT_NEAR(237.80861559081677, calibration_variable->cy(), 1.0e-3); +} + +TEST(Fixed3DLandmarkSimpleCovarianceConstraint, Serialization) +{ + // Construct a constraint + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + + PinholeCameraFixed calibration_variable(0); + calibration_variable.fx() = 638.34478759765620; + calibration_variable.fy() = 643.10717773437500; + calibration_variable.cx() = 310.29060457226840; + calibration_variable.cy() = 237.80861559081677; + + double marker_size = 1.0; + + fuse_core::Vector7d mean; + mean << 1.0, 2.0, 3.0, 1.0, 0.0, 0.0, 0.0; + + // Generated PD matrix using Octave: R = rand(6, 6); A = R * R' (use format long g to get the required precision) + fuse_core::Matrix2d cov; + cov << 0.25, 0.0, // NOLINT + 0.0, 0.25; // NOLINT + + // And observations... + Eigen::Matrix obs; + obs << 261.71822455, 168.60442225, 261.71822455, 307.01280893, 352.44745875, 177.74503448, 352.44745875, 297.87219670; + + Fixed3DLandmarkSimpleCovarianceConstraint expected("test", position_variable, orientation_variable, + calibration_variable, marker_size, obs, mean, cov); + + // Serialize the constraint into an archive + std::stringstream stream; + { + fuse_core::TextOutputArchive archive(stream); + expected.serialize(archive); + } + + // Deserialize a new constraint from that same stream + Fixed3DLandmarkSimpleCovarianceConstraint actual; + { + fuse_core::TextInputArchive archive(stream); + actual.deserialize(archive); + } + + // Compare + EXPECT_EQ(expected.uuid(), actual.uuid()); + EXPECT_EQ(expected.variables(), actual.variables()); + EXPECT_MATRIX_EQ(expected.mean(), actual.mean()); + EXPECT_MATRIX_EQ(expected.pts3d(), actual.pts3d()); + EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation()); + EXPECT_MATRIX_EQ(expected.observations(), actual.observations()); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/fuse_constraints/test/test_reprojection_error_constraint.cpp b/fuse_constraints/test/test_reprojection_error_constraint.cpp new file mode 100644 index 000000000..08e6da5c9 --- /dev/null +++ b/fuse_constraints/test/test_reprojection_error_constraint.cpp @@ -0,0 +1,315 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Fri Nov 17 2023 + * + * Copyright (c) 2023 Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +using fuse_constraints::ReprojectionErrorConstraint; +using fuse_variables::Orientation3DStamped; +using fuse_variables::PinholeCameraFixed; +using fuse_variables::Point3DLandmark; +using fuse_variables::Point3DFixedLandmark; +using fuse_variables::Position3DStamped; + +TEST(ReprojectionErrorConstraint, Constructor) +{ + // Construct a constraint just to make sure it compiles. + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Point3DLandmark point(0); + PinholeCameraFixed calibration_variable(0); + + fuse_core::Vector2d mean; + mean << 320.0, 240.0; // Centre of a 640x480 camera + + // Assume Half a pixel Variance + fuse_core::Matrix2d cov; + cov << 0.25, 0.00, // NOLINT + 0.00, 0.25; // NOLINT + + EXPECT_NO_THROW(ReprojectionErrorConstraint constraint("test", position_variable, orientation_variable, + calibration_variable, mean, cov)); +} + +TEST(ReprojectionErrorConstraint, Covariance) +{ + // Verify the covariance <--> sqrt information conversions are correct + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("mo")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("mo")); + Point3DLandmark point(0); + PinholeCameraFixed calibration_variable(0); + + fuse_core::Vector2d mean; + mean << 320.0, 240.0; // Centre of a 640x480 camera + + // Assume Half a pixel Variance + fuse_core::Matrix2d cov; + cov << 0.25, 0.00, // NOLINT + 0.00, 0.25; // NOLINT + + ReprojectionErrorConstraint constraint("test", position_variable, orientation_variable, calibration_variable, mean, + cov); + + // Define the expected matrices (used Octave to compute sqrt_info: 'chol(inv(A))') + fuse_core::Matrix2d expected_sqrt_info; + expected_sqrt_info << 2, 0, // NOLINT + 0, 2; // NOLINT + fuse_core::Matrix2d expected_cov = cov; + + // Compare + EXPECT_MATRIX_NEAR(expected_cov, constraint.covariance(), 1.0e-9); + EXPECT_MATRIX_NEAR(expected_sqrt_info, constraint.sqrtInformation(), 1.0e-9); +} + +TEST(ReprojectionErrorConstraint, Optimization) +{ + // Optimize a single pose and single constraint, verify the expected value and covariance are generated. + // Create the variables + auto position_variable = Position3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + position_variable->x() = 1.5; + position_variable->y() = -3.0; + position_variable->z() = 10.0; + + auto orientation_variable = Orientation3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + orientation_variable->w() = 0.952; + orientation_variable->x() = 0.038; + orientation_variable->y() = -0.189; + orientation_variable->z() = 0.239; + + auto calibration_variable = PinholeCameraFixed::make_shared(0); + calibration_variable->fx() = 638.34478759765620; + calibration_variable->fy() = 643.10717773437500; + calibration_variable->cx() = 310.29060457226840; + calibration_variable->cy() = 237.80861559081677; + + std::vector point_variables; + point_variables.push_back(Point3DFixedLandmark::make_shared(0)); + point_variables.push_back(Point3DFixedLandmark::make_shared(1)); + point_variables.push_back(Point3DFixedLandmark::make_shared(2)); + point_variables.push_back(Point3DFixedLandmark::make_shared(3)); + point_variables[0]->array() = {-0.70710681, -1.0, 9.29289324}; + point_variables[1]->array() = {-0.70710681, 1.0, 9.29289324}; + point_variables[2]->array() = { 0.70710681, -1.0, 10.70710676}; + point_variables[3]->array() = { 0.70710681, 1.0, 10.70710676}; + + // Create an observation + std::vector means(4); + means[0] << 261.71822455, 168.60442225; + means[1] << 261.71822455, 307.01280893; + means[2] << 352.44745875, 177.74503448; + means[3] << 352.44745875, 297.87219670; + + // Define Observation Covariance + fuse_core::Matrix2d cov; + cov << 0.25, 0.00, // NOLINT + 0.00, 0.25; // NOLINT + + ceres::Problem::Options problem_options; + problem_options.loss_function_ownership = fuse_core::Loss::Ownership; + ceres::Problem problem(problem_options); + + // Build the problem + problem.AddParameterBlock(position_variable->data(), position_variable->size(), + position_variable->localParameterization()); + problem.AddParameterBlock(orientation_variable->data(), orientation_variable->size(), + orientation_variable->localParameterization()); + problem.AddParameterBlock(calibration_variable->data(), calibration_variable->size(), + calibration_variable->localParameterization()); + + if (calibration_variable->holdConstant()) + { + problem.SetParameterBlockConstant(calibration_variable->data()); + } + + for (uint i = 0; i < point_variables.size(); i++) + { + auto constraint = ReprojectionErrorConstraint::make_shared("test", + *position_variable, *orientation_variable, + *calibration_variable, means[i], cov); + + problem.AddParameterBlock(point_variables[i]->data(), point_variables[i]->size(), + point_variables[i]->localParameterization()); + + std::vector parameter_blocks; + parameter_blocks.push_back(position_variable->data()); + parameter_blocks.push_back(orientation_variable->data()); + parameter_blocks.push_back(calibration_variable->data()); + parameter_blocks.push_back(point_variables[i]->data()); + + problem.SetParameterBlockConstant(point_variables[i]->data()); + problem.AddResidualBlock(constraint->costFunction(), constraint->lossFunction(), parameter_blocks); + } + + // Run the solver + ceres::Solver::Options options; + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + + // Check + EXPECT_NEAR(0.00, position_variable->x(), 1.0e-5); + EXPECT_NEAR(0.00, position_variable->y(), 1.0e-5); + EXPECT_NEAR(0.00, position_variable->z(), 1.0e-5); + + EXPECT_NEAR(1.0, orientation_variable->w(), 1.0e-3); + EXPECT_NEAR(0.00, orientation_variable->x(), 1.0e-3); + EXPECT_NEAR(0.00, orientation_variable->y(), 1.0e-3); + EXPECT_NEAR(0.00, orientation_variable->z(), 1.0e-3); + + EXPECT_NEAR(638.34478759765620, calibration_variable->fx(), 1.0e-3); + EXPECT_NEAR(643.10717773437500, calibration_variable->fy(), 1.0e-3); + EXPECT_NEAR(310.29060457226840, calibration_variable->cx(), 1.0e-3); + EXPECT_NEAR(237.80861559081677, calibration_variable->cy(), 1.0e-3); + + EXPECT_NEAR(-0.70710681, point_variables[0]->x(), 1.0e-3); + EXPECT_NEAR(-1.0, point_variables[0]->y(), 1.0e-3); + EXPECT_NEAR(9.29289324, point_variables[0]->z(), 1.0e-3); + + EXPECT_NEAR(-0.70710681, point_variables[1]->x(), 1.0e-3); + EXPECT_NEAR(1.0, point_variables[1]->y(), 1.0e-3); + EXPECT_NEAR(9.29289324, point_variables[1]->z(), 1.0e-3); + + EXPECT_NEAR(0.70710681, point_variables[2]->x(), 1.0e-3); + EXPECT_NEAR(-1.0, point_variables[2]->y(), 1.0e-3); + EXPECT_NEAR(10.70710676, point_variables[2]->z(), 1.0e-3); + + EXPECT_NEAR(0.70710681, point_variables[3]->x(), 1.0e-3); + EXPECT_NEAR(1.0, point_variables[3]->y(), 1.0e-3); + EXPECT_NEAR(10.70710676, point_variables[3]->z(), 1.0e-3); + + // // Compute the covariance + // std::vector > covariance_blocks; + // covariance_blocks.emplace_back(position_variable->data(), position_variable->data()); + // covariance_blocks.emplace_back(orientation_variable->data(), orientation_variable->data()); + // covariance_blocks.emplace_back(position_variable->data(), orientation_variable->data()); + + // ceres::Covariance::Options cov_options; + // ceres::Covariance covariance(cov_options); + // covariance.Compute(covariance_blocks, &problem); + // fuse_core::MatrixXd cov_pos_pos(position_variable->size(), position_variable->size()); + // covariance.GetCovarianceBlock(position_variable->data(), position_variable->data(), cov_pos_pos.data()); + + // fuse_core::MatrixXd cov_or_or(orientation_variable->localSize(), orientation_variable->localSize()); + // covariance.GetCovarianceBlockInTangentSpace( + // orientation_variable->data(), orientation_variable->data(), cov_or_or.data()); + + // fuse_core::MatrixXd cov_pos_or(position_variable->localSize(), orientation_variable->localSize()); + // covariance.GetCovarianceBlockInTangentSpace( + // position_variable->data(), orientation_variable->data(), cov_pos_or.data()); + + // // Assemble the full covariance from the covariance blocks + // fuse_core::Matrix6d actual_covariance; + // actual_covariance << cov_pos_pos, cov_pos_or, cov_pos_or.transpose(), cov_or_or; + + // // Define the expected covariance + // fuse_core::Matrix6d expected_covariance; + // expected_covariance << + // 1.0, 0.1, 0.2, 0.3, 0.4, 0.5, + // 0.1, 2.0, 0.6, 0.5, 0.4, 0.3, + // 0.2, 0.6, 3.0, 0.2, 0.1, 0.2, + // 0.3, 0.5, 0.2, 4.0, 0.3, 0.4, + // 0.4, 0.4, 0.1, 0.3, 5.0, 0.5, + // 0.5, 0.3, 0.2, 0.4, 0.5, 6.0; + + // EXPECT_MATRIX_NEAR(expected_covariance, actual_covariance, 1.0e-5); +} + +TEST(ReprojectionErrorConstraint, Serialization) +{ + // Construct a constraint + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + + PinholeCameraFixed calibration_variable(0); + calibration_variable.fx() = 638.34478759765620; + calibration_variable.fy() = 643.10717773437500; + calibration_variable.cx() = 310.29060457226840; + calibration_variable.cy() = 237.80861559081677; + + fuse_core::Vector2d mean; + mean << 261.71822455, 168.60442225; + + // Generated PD matrix using Octave: R = rand(6, 6); A = R * R' (use format long g to get the required precision) + fuse_core::Matrix2d cov; + cov << 0.25, 0.00, //NOLINT + 0.00, 0.25; //NOLINT + + + ReprojectionErrorConstraint expected("test", position_variable, + orientation_variable, calibration_variable, + mean, cov); + + // Serialize the constraint into an archive + std::stringstream stream; + { + fuse_core::TextOutputArchive archive(stream); + expected.serialize(archive); + } + + // Deserialize a new constraint from that same stream + ReprojectionErrorConstraint actual; + { + fuse_core::TextInputArchive archive(stream); + actual.deserialize(archive); + } + + // Compare + EXPECT_EQ(expected.uuid(), actual.uuid()); + EXPECT_EQ(expected.variables(), actual.variables()); + EXPECT_MATRIX_EQ(expected.mean(), actual.mean()); + EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation()); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/fuse_constraints/test/test_reprojection_error_snavelly_constraint.cpp b/fuse_constraints/test/test_reprojection_error_snavelly_constraint.cpp new file mode 100644 index 000000000..51d4eaeb9 --- /dev/null +++ b/fuse_constraints/test/test_reprojection_error_snavelly_constraint.cpp @@ -0,0 +1,309 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created on Fri Nov 17 2023 + * + * Copyright (c) 2023 Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +using fuse_constraints::ReprojectionErrorSnavellyConstraint; +using fuse_variables::Orientation3DStamped; +using fuse_variables::PinholeCameraSimple; +using fuse_variables::Point3DLandmark; +using fuse_variables::Point3DFixedLandmark; +using fuse_variables::Position3DStamped; + +TEST(ReprojectionErrorSnavellyConstraint, Constructor) +{ + // Construct a constraint just to make sure it compiles. + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Point3DLandmark point(0); + PinholeCameraSimple calibration_variable(0); + + fuse_core::Vector2d mean; + mean << 320.0, 240.0; // Centre of a 640x480 camera + + // Assume Half a pixel Variance + fuse_core::Matrix2d cov; + cov << 0.25, 0.00, // NOLINT + 0.00, 0.25; // NOLINT + + EXPECT_NO_THROW(ReprojectionErrorSnavellyConstraint constraint("test", position_variable, orientation_variable, + calibration_variable, mean, cov)); +} + +TEST(ReprojectionErrorSnavellyConstraint, Covariance) +{ + // Verify the covariance <--> sqrt information conversions are correct + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("mo")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("mo")); + Point3DLandmark point(0); + PinholeCameraSimple calibration_variable(0); + + fuse_core::Vector2d mean; + mean << 320.0, 240.0; // Centre of a 640x480 camera + + // Assume Half a pixel Variance + fuse_core::Matrix2d cov; + cov << 0.25, 0.00, // NOLINT + 0.00, 0.25; // NOLINT + + ReprojectionErrorSnavellyConstraint constraint("test", position_variable, orientation_variable, + calibration_variable, mean, cov); + + // Define the expected matrices (used Octave to compute sqrt_info: 'chol(inv(A))') + fuse_core::Matrix2d expected_sqrt_info; + expected_sqrt_info << 2, 0, // NOLINT + 0, 2; // NOLINT + fuse_core::Matrix2d expected_cov = cov; + + // Compare + EXPECT_MATRIX_NEAR(expected_cov, constraint.covariance(), 1.0e-9); + EXPECT_MATRIX_NEAR(expected_sqrt_info, constraint.sqrtInformation(), 1.0e-9); +} + +TEST(ReprojectionErrorSnavellyConstraint, Optimization) +{ + // Optimize a single pose and single constraint, verify the expected value and covariance are generated. + // Create the variables + auto position_variable = Position3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + position_variable->x() = 1.5; + position_variable->y() = -3.0; + position_variable->z() = -1.0; + + auto orientation_variable = Orientation3DStamped::make_shared(ros::Time(1, 0), fuse_core::uuid::generate("spra")); + orientation_variable->w() = 0.952; + orientation_variable->x() = 0.038; + orientation_variable->y() = -0.189; + orientation_variable->z() = 0.239; + + auto calibration_variable = PinholeCameraSimple::make_shared(0); + calibration_variable->f() = 638.34478759765620; + calibration_variable->r1() = 0.13281739520782995; + calibration_variable->r2() = -0.17255676937880005; + + std::vector point_variables; + point_variables.push_back(Point3DFixedLandmark::make_shared(0)); + point_variables.push_back(Point3DFixedLandmark::make_shared(1)); + point_variables.push_back(Point3DFixedLandmark::make_shared(2)); + point_variables.push_back(Point3DFixedLandmark::make_shared(3)); + point_variables[0]->array() = {-0.70710681, -1.0, 9.29289324}; + point_variables[1]->array() = {-0.70710681, 1.0, 9.29289324}; + point_variables[2]->array() = { 0.70710681, -1.0, 10.70710676}; + point_variables[3]->array() = { 0.70710681, 1.0, 10.70710676}; + + // Create an observation + std::vector means(4); + means[0] << 48.60945112, 68.79577411; + means[1] << 48.60945112, -68.79577411; + means[2] << -42.18113651, 59.68708153; + means[3] << -42.18113651, -59.68708150; + + // Define Observation Covariance + fuse_core::Matrix2d cov; + cov << 0.25, 0.00, // NOLINT + 0.00, 0.25; // NOLINT + + ceres::Problem::Options problem_options; + problem_options.loss_function_ownership = fuse_core::Loss::Ownership; + ceres::Problem problem(problem_options); + + // Build the problem + problem.AddParameterBlock(position_variable->data(), position_variable->size(), + position_variable->localParameterization()); + problem.AddParameterBlock(orientation_variable->data(), orientation_variable->size(), + orientation_variable->localParameterization()); + problem.AddParameterBlock(calibration_variable->data(), calibration_variable->size(), + calibration_variable->localParameterization()); + + problem.SetParameterBlockConstant(calibration_variable->data()); + + for (uint i = 0; i < point_variables.size(); i++) + { + auto constraint = ReprojectionErrorSnavellyConstraint::make_shared("test", + *position_variable, *orientation_variable, + *calibration_variable, means[i], cov); + + problem.AddParameterBlock(point_variables[i]->data(), point_variables[i]->size(), + point_variables[i]->localParameterization()); + + std::vector parameter_blocks; + parameter_blocks.push_back(position_variable->data()); + parameter_blocks.push_back(orientation_variable->data()); + parameter_blocks.push_back(calibration_variable->data()); + parameter_blocks.push_back(point_variables[i]->data()); + + problem.SetParameterBlockConstant(point_variables[i]->data()); + problem.AddResidualBlock(constraint->costFunction(), constraint->lossFunction(), parameter_blocks); + } + + // Run the solver + ceres::Solver::Options options; + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + + // Check + EXPECT_NEAR(0.00, position_variable->x(), 1.0e-2); // 1cm error (too few points for more accuracy) + EXPECT_NEAR(0.00, position_variable->y(), 1.0e-2); + EXPECT_NEAR(0.00, position_variable->z(), 1.0e-2); + + EXPECT_NEAR(1.0, orientation_variable->w(), 1.0e-3); + EXPECT_NEAR(0.00, orientation_variable->x(), 1.0e-3); + EXPECT_NEAR(0.00, orientation_variable->y(), 1.0e-3); + EXPECT_NEAR(0.00, orientation_variable->z(), 1.0e-3); + + EXPECT_NEAR(638.34478759765620, calibration_variable->f(), 1.0e-3); + EXPECT_NEAR(0.13281739520782995, calibration_variable->r1(), 1.0e-3); + EXPECT_NEAR(-0.17255676937880005, calibration_variable->r2(), 1.0e-3); + + EXPECT_NEAR(-0.70710681, point_variables[0]->x(), 1.0e-3); + EXPECT_NEAR(-1.0, point_variables[0]->y(), 1.0e-3); + EXPECT_NEAR(9.29289324, point_variables[0]->z(), 1.0e-3); + + EXPECT_NEAR(-0.70710681, point_variables[1]->x(), 1.0e-3); + EXPECT_NEAR(1.0, point_variables[1]->y(), 1.0e-3); + EXPECT_NEAR(9.29289324, point_variables[1]->z(), 1.0e-3); + + EXPECT_NEAR(0.70710681, point_variables[2]->x(), 1.0e-3); + EXPECT_NEAR(-1.0, point_variables[2]->y(), 1.0e-3); + EXPECT_NEAR(10.70710676, point_variables[2]->z(), 1.0e-3); + + EXPECT_NEAR(0.70710681, point_variables[3]->x(), 1.0e-3); + EXPECT_NEAR(1.0, point_variables[3]->y(), 1.0e-3); + EXPECT_NEAR(10.70710676, point_variables[3]->z(), 1.0e-3); + + // // Compute the covariance + // std::vector > covariance_blocks; + // covariance_blocks.emplace_back(position_variable->data(), position_variable->data()); + // covariance_blocks.emplace_back(orientation_variable->data(), orientation_variable->data()); + // covariance_blocks.emplace_back(position_variable->data(), orientation_variable->data()); + + // ceres::Covariance::Options cov_options; + // ceres::Covariance covariance(cov_options); + // covariance.Compute(covariance_blocks, &problem); + // fuse_core::MatrixXd cov_pos_pos(position_variable->size(), position_variable->size()); + // covariance.GetCovarianceBlock(position_variable->data(), position_variable->data(), cov_pos_pos.data()); + + // fuse_core::MatrixXd cov_or_or(orientation_variable->localSize(), orientation_variable->localSize()); + // covariance.GetCovarianceBlockInTangentSpace( + // orientation_variable->data(), orientation_variable->data(), cov_or_or.data()); + + // fuse_core::MatrixXd cov_pos_or(position_variable->localSize(), orientation_variable->localSize()); + // covariance.GetCovarianceBlockInTangentSpace( + // position_variable->data(), orientation_variable->data(), cov_pos_or.data()); + + // // Assemble the full covariance from the covariance blocks + // fuse_core::Matrix6d actual_covariance; + // actual_covariance << cov_pos_pos, cov_pos_or, cov_pos_or.transpose(), cov_or_or; + + // // Define the expected covariance + // fuse_core::Matrix6d expected_covariance; + // expected_covariance << + // 1.0, 0.1, 0.2, 0.3, 0.4, 0.5, + // 0.1, 2.0, 0.6, 0.5, 0.4, 0.3, + // 0.2, 0.6, 3.0, 0.2, 0.1, 0.2, + // 0.3, 0.5, 0.2, 4.0, 0.3, 0.4, + // 0.4, 0.4, 0.1, 0.3, 5.0, 0.5, + // 0.5, 0.3, 0.2, 0.4, 0.5, 6.0; + + // EXPECT_MATRIX_NEAR(expected_covariance, actual_covariance, 1.0e-5); +} + +TEST(ReprojectionErrorSnavellyConstraint, Serialization) +{ + // Construct a constraint + Position3DStamped position_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + Orientation3DStamped orientation_variable(ros::Time(1234, 5678), fuse_core::uuid::generate("walle")); + + PinholeCameraSimple calibration_variable(0); + calibration_variable.f() = 638.34478759765620; + calibration_variable.r1() = 0.13281739520782995; + calibration_variable.r2() = -0.17255676937880005; + + fuse_core::Vector2d mean; + mean << 261.71822455, 168.60442225; + + // Generated PD matrix using Octave: R = rand(6, 6); A = R * R' (use format long g to get the required precision) + fuse_core::Matrix2d cov; + cov << 0.25, 0.00, //NOLINT + 0.00, 0.25; //NOLINT + + + ReprojectionErrorSnavellyConstraint expected("test", position_variable, + orientation_variable, calibration_variable, + mean, cov); + + // Serialize the constraint into an archive + std::stringstream stream; + { + fuse_core::TextOutputArchive archive(stream); + expected.serialize(archive); + } + + // Deserialize a new constraint from that same stream + ReprojectionErrorSnavellyConstraint actual; + { + fuse_core::TextInputArchive archive(stream); + actual.deserialize(archive); + } + + // Compare + EXPECT_EQ(expected.uuid(), actual.uuid()); + EXPECT_EQ(expected.variables(), actual.variables()); + EXPECT_MATRIX_EQ(expected.mean(), actual.mean()); + EXPECT_MATRIX_EQ(expected.sqrtInformation(), actual.sqrtInformation()); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/fuse_variables/CMakeLists.txt b/fuse_variables/CMakeLists.txt index e09f5a868..6c4e0dae1 100644 --- a/fuse_variables/CMakeLists.txt +++ b/fuse_variables/CMakeLists.txt @@ -36,6 +36,7 @@ add_library(${PROJECT_NAME} src/acceleration_linear_3d_stamped.cpp src/pinhole_camera.cpp src/pinhole_camera_fixed.cpp + src/pinhole_camera_simple.cpp src/orientation_2d_stamped.cpp src/orientation_3d_stamped.cpp src/point_2d_fixed_landmark.cpp @@ -246,6 +247,30 @@ if(CATKIN_ENABLE_TESTING) CXX_STANDARD_REQUIRED YES ) + # Camera Intrinsics tests + catkin_add_gtest(test_pinhole_camera_simple + test/test_pinhole_camera_simple.cpp + ) + add_dependencies(test_pinhole_camera_simple + ${catkin_EXPORTED_TARGETS} + ) + target_include_directories(test_pinhole_camera_simple + PRIVATE + include + ${catkin_INCLUDE_DIRS} + ${CERES_INCLUDE_DIRS} + ) + target_link_libraries(test_pinhole_camera_simple + ${PROJECT_NAME} + ${catkin_LIBRARIES} + ${CERES_LIBRARIES} + ) + set_target_properties(test_pinhole_camera_simple + PROPERTIES + CXX_STANDARD 17 + CXX_STANDARD_REQUIRED YES + ) + # Fixed Size Variable Tests catkin_add_gtest(test_fixed_size_variable test/test_fixed_size_variable.cpp diff --git a/fuse_variables/include/fuse_variables/base_camera.h b/fuse_variables/include/fuse_variables/base_camera.h new file mode 100644 index 000000000..cdbe39e0a --- /dev/null +++ b/fuse_variables/include/fuse_variables/base_camera.h @@ -0,0 +1,130 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created: 11.13.2023 + * + * Copyright (c) 2023, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef FUSE_VARIABLES_BASE_CAMERA_H +#define FUSE_VARIABLES_BASE_CAMERA_H + +#include +#include +#include +#include + +#include +#include +#include + +#include + +namespace fuse_variables +{ +/** + * @brief Variable representing intrinsic parameters of a camera. + * + * The UUID of this class is constant after + * construction and dependent on a user input database id. As such, the database id cannot be altered after + * construction. + */ +template +class BaseCamera : public FixedSizeVariable +{ +public: + FUSE_VARIABLE_DEFINITIONS(BaseCamera); + + /** + * @brief Default constructor + */ + BaseCamera() = default; + + /** + * @brief Construct a pinhole camera variable given a camera id and intrinsic parameters + * + * @param[in] camera_id The id associated to a camera + */ + explicit BaseCamera(const fuse_core::UUID& uuid, const uint64_t& camera_id): + FixedSizeVariable(uuid), id_(camera_id){}; + + /** + * @brief Construct a pinhole camera variable given a camera id + * + * @param[in] camera_id The id associated to a camera + */ + explicit BaseCamera(const uint64_t& camera_id): + BaseCamera(fuse_core::uuid::generate(detail::type(), camera_id), camera_id){}; + + /** + * @brief Read-only access to the id + */ + const uint64_t& id() const { return id_; } + + /** + * @brief Print a human-readable description of the variable to the provided + * stream. + * + * @param[out] stream The stream to write to. Defaults to stdout. + */ + void print(std::ostream& stream = std::cout) const override + { + stream << type() << ":\n" + << " uuid: " << this->uuid() << "\n" + << " size: " << this->size() << "\n" + << " camera id: " << id() << "\n"; + }; + +private: + // Allow Boost Serialization access to private methods + friend class boost::serialization::access; + uint64_t id_ { 0 }; + + /** + * @brief The Boost Serialize method that serializes all of the data members + * in to/out of the archive + * + * @param[in/out] archive - The archive object that holds the serialized class + * members + * @param[in] version - The version of the archive being read/written. + * Generally unused. + */ + template + void serialize(Archive& archive, const unsigned int /* version */) + { + archive& boost::serialization::base_object>(*this); + archive& id_; + } +}; + +} // namespace fuse_variables + +#endif // FUSE_VARIABLES_BASE_CAMERA_H diff --git a/fuse_variables/include/fuse_variables/pinhole_camera.h b/fuse_variables/include/fuse_variables/pinhole_camera.h index c967cdff1..ac1f0ece5 100644 --- a/fuse_variables/include/fuse_variables/pinhole_camera.h +++ b/fuse_variables/include/fuse_variables/pinhole_camera.h @@ -40,6 +40,7 @@ #include #include #include +#include #include #include @@ -57,7 +58,7 @@ namespace fuse_variables * construction and dependent on a user input database id. As such, the database id cannot be altered after * construction. */ -class PinholeCamera : public FixedSizeVariable<4> +class PinholeCamera : public BaseCamera<4> { public: FUSE_VARIABLE_DEFINITIONS(PinholeCamera); @@ -137,7 +138,7 @@ class PinholeCamera : public FixedSizeVariable<4> /** * @brief Read-only access to the id */ - const uint64_t& id() const { return id_; } + // const uint64_t& id() const { return id_; } /** * @brief Print a human-readable description of the variable to the provided @@ -149,16 +150,16 @@ class PinholeCamera : public FixedSizeVariable<4> protected: /** - * @brief Construct a point 3D variable given a landmarks id + * @brief Construct a pinhole given a camera_id * - * @param[in] landmark_id The id associated to a landmark + * @param[in] camera_id The id associated to a camera_id */ - PinholeCamera(const fuse_core::UUID& uuid, const uint64_t& landmark_id); + PinholeCamera(const fuse_core::UUID& uuid, const uint64_t& camera_id); private: // Allow Boost Serialization access to private methods friend class boost::serialization::access; - uint64_t id_ { 0 }; + // uint64_t id_ { 0 }; /** * @brief The Boost Serialize method that serializes all of the data members @@ -172,8 +173,7 @@ class PinholeCamera : public FixedSizeVariable<4> template void serialize(Archive& archive, const unsigned int /* version */) { - archive& boost::serialization::base_object>(*this); - archive& id_; + archive& boost::serialization::base_object>(*this); } }; diff --git a/fuse_variables/include/fuse_variables/pinhole_camera_simple.h b/fuse_variables/include/fuse_variables/pinhole_camera_simple.h new file mode 100644 index 000000000..03862e89e --- /dev/null +++ b/fuse_variables/include/fuse_variables/pinhole_camera_simple.h @@ -0,0 +1,167 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created: 11.13.2023 + * + * Copyright (c) 2023, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#ifndef FUSE_VARIABLES_PINHOLE_CAMERA_H +#define FUSE_VARIABLES_PINHOLE_CAMERA_H + +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +namespace fuse_variables +{ +/** + * @brief Variable representing intrinsic parameters of a camera. + * + * The UUID of this class is constant after + * construction and dependent on a user input database id. As such, the database id cannot be altered after + * construction. + */ +class PinholeCameraSimple : public BaseCamera<3> +{ +public: + FUSE_VARIABLE_DEFINITIONS(PinholeCameraSimple); + + /** + * @brief Can be used to directly index variables in the data array + */ + enum : size_t + { + F = 0, + R1 = 1, + R2 = 2 + }; + + /** + * @brief Default constructor + */ + PinholeCameraSimple() = default; + + /** + * @brief Construct a pinhole camera variable given a camera id + * + * @param[in] camera_id The id associated to a camera + */ + explicit PinholeCameraSimple(const uint64_t& camera_id); + + /** + * @brief Construct a pinhole camera variable given a camera id and intrinsic parameters + * + * @param[in] camera_id The id associated to a camera + */ + explicit PinholeCameraSimple(const fuse_core::UUID& uuid, const uint64_t& camera_id, + const double& f, const double& r1, const double& r2); + + /** + * @brief Read-write access to the cx parameter. + */ + double& f() { return data_[F]; } + + /** + * @brief Read-only access to the cx parameter. + */ + const double& f() const { return data_[F]; } + + /** + * @brief Read-write access to the cy parameter. + */ + double& r1() { return data_[R1]; } + + /** + * @brief Read-only access to the cy parameter. + */ + const double& r1() const { return data_[R1]; } + + /** + * @brief Read-write access to the fx parameter. + */ + double& r2() { return data_[R2]; } + + /** + * @brief Read-only access to the fx parameter. + */ + const double& r2() const { return data_[R2]; } + + /** + * @brief Print a human-readable description of the variable to the provided + * stream. + * + * @param[out] stream The stream to write to. Defaults to stdout. + */ + void print(std::ostream& stream = std::cout) const override; + +protected: + /** + * @brief Construct a pinhole given a camera_id + * + * @param[in] camera_id The id associated to a camera_id + */ + PinholeCameraSimple(const fuse_core::UUID& uuid, const uint64_t& camera_id); + +private: + // Allow Boost Serialization access to private methods + friend class boost::serialization::access; + // uint64_t id_ { 0 }; + + /** + * @brief The Boost Serialize method that serializes all of the data members + * in to/out of the archive + * + * @param[in/out] archive - The archive object that holds the serialized class + * members + * @param[in] version - The version of the archive being read/written. + * Generally unused. + */ + template + void serialize(Archive& archive, const unsigned int /* version */) + { + archive& boost::serialization::base_object>(*this); + } +}; + +} // namespace fuse_variables + +BOOST_CLASS_EXPORT_KEY(fuse_variables::PinholeCameraSimple); + +#endif // FUSE_VARIABLES_PINHOLE_CAMERA_H diff --git a/fuse_variables/src/pinhole_camera.cpp b/fuse_variables/src/pinhole_camera.cpp index ec665c7af..30883df22 100644 --- a/fuse_variables/src/pinhole_camera.cpp +++ b/fuse_variables/src/pinhole_camera.cpp @@ -48,7 +48,7 @@ namespace fuse_variables { PinholeCamera::PinholeCamera(const fuse_core::UUID& uuid, const uint64_t& camera_id) - : FixedSizeVariable(uuid), id_(camera_id) + : BaseCamera(uuid, camera_id) { } @@ -73,12 +73,12 @@ void PinholeCamera::print(std::ostream& stream) const stream << type() << ":\n" << " uuid: " << uuid() << "\n" << " size: " << size() << "\n" - << " landmark id: " << id() << "\n" + << " camera id: " << id() << "\n" << " data:\n" - << " - cx: " << cx() << "\n" - << " - cy: " << cy() << "\n" << " - fx: " << fx() << "\n" - << " - fy: " << fy() << "\n"; + << " - fy: " << fy() << "\n" + << " - cx: " << cx() << "\n" + << " - cy: " << cy() << "\n"; } } // namespace fuse_variables diff --git a/fuse_variables/src/pinhole_camera_simple.cpp b/fuse_variables/src/pinhole_camera_simple.cpp new file mode 100644 index 000000000..10a51b528 --- /dev/null +++ b/fuse_variables/src/pinhole_camera_simple.cpp @@ -0,0 +1,84 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created: 11.13.2023 + * + * Copyright (c) 2023, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include + +#include +#include +#include +#include + +#include + +#include + +namespace fuse_variables +{ +PinholeCameraSimple::PinholeCameraSimple(const fuse_core::UUID& uuid, const uint64_t& camera_id) + : BaseCamera(uuid, camera_id) +{ +} + +PinholeCameraSimple::PinholeCameraSimple(const uint64_t& camera_id) + : PinholeCameraSimple(fuse_core::uuid::generate(detail::type(), camera_id), camera_id) +{ +} + +PinholeCameraSimple::PinholeCameraSimple(const fuse_core::UUID& uuid, const uint64_t& camera_id, + const double& f, const double& r1, const double& r2) + : PinholeCameraSimple(fuse_core::uuid::generate(detail::type(), camera_id), camera_id) +{ + data_[F] = f; + data_[R1] = r1; + data_[R2] = r2; +} + +void PinholeCameraSimple::print(std::ostream& stream) const +{ + stream << type() << ":\n" + << " uuid: " << uuid() << "\n" + << " size: " << size() << "\n" + << " camera id: " << id() << "\n" + << " data:\n" + << " - f: " << f() << "\n" + << " - r1: " << r1() << "\n" + << " - r2: " << r2() << "\n"; +} + +} // namespace fuse_variables + +BOOST_CLASS_EXPORT_IMPLEMENT(fuse_variables::PinholeCameraSimple); +PLUGINLIB_EXPORT_CLASS(fuse_variables::PinholeCameraSimple, fuse_core::Variable); diff --git a/fuse_variables/test/test_pinhole_camera_simple.cpp b/fuse_variables/test/test_pinhole_camera_simple.cpp new file mode 100644 index 000000000..93c3510f3 --- /dev/null +++ b/fuse_variables/test/test_pinhole_camera_simple.cpp @@ -0,0 +1,156 @@ +/* + * Software License Agreement (BSD License) + * + * Author: Oscar Mendez + * Created: 11.13.2023 + * + * Copyright (c) 2021, Locus Robotics + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of the copyright holder nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +using fuse_variables::PinholeCameraSimple; + +TEST(PinholeCameraSimpleSimple, Type) +{ + PinholeCameraSimple variable(0); + EXPECT_EQ("fuse_variables::PinholeCameraSimple", variable.type()); +} + +TEST(PinholeCameraSimple, UUID) +{ + // Verify two positions with the same landmark ids produce the same uuids + { + PinholeCameraSimple variable1(0); + PinholeCameraSimple variable2(0); + EXPECT_EQ(variable1.uuid(), variable2.uuid()); + } + + // Verify two positions with the different landmark ids produce different uuids + { + PinholeCameraSimple variable1(0); + PinholeCameraSimple variable2(1); + EXPECT_NE(variable1.uuid(), variable2.uuid()); + } +} + +struct CostFunctor +{ + CostFunctor() + { + } + + template + bool operator()(const T* const k, T* residual) const + { + residual[0] = k[0] - T(1.2); + residual[1] = k[1] + T(0.8); + residual[2] = k[2] - T(0.51); + + return true; + } +}; + +TEST(PinholeCameraSimple, Optimization) +{ + // Create a Point3DLandmark + PinholeCameraSimple K(0); + K.f() = 4.1; + K.r1() = 3.5; + K.r2() = 5; + + // Create a simple a constraint + ceres::CostFunction* cost_function = new ceres::AutoDiffCostFunction(new CostFunctor()); + + // Build the problem. + ceres::Problem problem; + problem.AddParameterBlock(K.data(), K.size()); + std::vector parameter_blocks; + parameter_blocks.push_back(K.data()); + problem.AddResidualBlock(cost_function, nullptr, parameter_blocks); + + // Run the solver + ceres::Solver::Options options; + options.linear_solver_type = ceres::DENSE_SCHUR; + ceres::Solver::Summary summary; + ceres::Solve(options, &problem, &summary); + + // Check + EXPECT_NEAR(1.2, K.f(), 1.0e-5); + EXPECT_NEAR(-0.8, K.r1(), 1.0e-5); + EXPECT_NEAR(0.51, K.r2(), 1.0e-5); +} + +TEST(PinholeCameraSimple, Serialization) +{ + // Create a Point3DLandmark + PinholeCameraSimple expected(0); + expected.f() = 640; + expected.r1() = 0.5; + expected.r2() = 0.5; + + // Serialize the variable into an archive + std::stringstream stream; + { + fuse_core::TextOutputArchive archive(stream); + expected.serialize(archive); + } + + // Deserialize a new variable from that same stream + PinholeCameraSimple actual; + { + fuse_core::TextInputArchive archive(stream); + actual.deserialize(archive); + } + + // Compare + EXPECT_EQ(expected.id(), actual.id()); + EXPECT_EQ(expected.uuid(), actual.uuid()); + EXPECT_EQ(expected.f(), actual.f()); + EXPECT_EQ(expected.r1(), actual.r1()); + EXPECT_EQ(expected.r2(), actual.r2()); +} + +int main(int argc, char** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +}