[
  {
    "path": ".gitignore",
    "content": "*.DS_Store\nbuild*\n"
  },
  {
    "path": "CHANGELOG",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for GP-SLAM\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n0.1.0 (2017-08-25)\n------------------\n* Initial release\n* Contributors: Jing Dong, Xinyan Yan\n\n"
  },
  {
    "path": "CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.6)\nenable_testing()\nproject(gpslam CXX C)\n\n# version indicator\nset(GPSLAM_VERSION_MAJOR 0)\nset(GPSLAM_VERSION_MINOR 1)\nset(GPSLAM_VERSION_PATCH 0)\nset(GPSLAM_VERSION_STRING \"${GPSLAM_VERSION_MAJOR}.${GPSLAM_VERSION_MINOR}.${GPSLAM_VERSION_PATCH}\")\n\n\n# Find dependent libraries\n\n# Find GTSAM components\nfind_package(GTSAM REQUIRED) # Uses installed package\ninclude_directories(${GTSAM_INCLUDE_DIR})\nset(GTSAM_LIBS gtsam)\n\nfind_package(GTSAMCMakeTools)\ninclude(GtsamMakeConfigFile)\ninclude(GtsamBuildTypes)\ninclude(GtsamTesting)\n\n# options\noption(GPSLAM_BUILD_MATLAB_TOOLBOX \"whether build matlab toolbox\" OFF)\n\n# for unittest scripts\nset(CMAKE_MODULE_PATH \"${CMAKE_MODULE_PATH}\" \"${GTSAM_DIR}/../GTSAMCMakeTools\")\n\n\n# Boost - same requirement as gtsam\nfind_package(Boost 1.46 REQUIRED)\nfind_package(Boost COMPONENTS filesystem REQUIRED)\nfind_package(Boost COMPONENTS system REQUIRED)\nfind_package(Boost COMPONENTS thread REQUIRED)\nfind_package(Boost COMPONENTS serialization REQUIRED)\n\ninclude_directories(${Boost_INCLUDE_DIR})\n\n\n# include current source folder, at the very beginning\ninclude_directories(BEFORE ${CMAKE_CURRENT_SOURCE_DIR})\n\n# Process source subdirs\nadd_subdirectory(gpslam)\n\n# Wrapping to MATLAB\nif(GPSLAM_BUILD_MATLAB_TOOLBOX)\n  include(GtsamMatlabWrap)\n  include_directories(${CMAKE_CURRENT_SOURCE_DIR})\n  wrap_and_install_library(gpslam.h ${PROJECT_NAME} \"${CMAKE_CURRENT_SOURCE_DIR}\" \"\")\nendif()\n\n# Install config and export files\nGtsamMakeConfigFile(gpslam)\nexport(TARGETS ${gpslam_EXPORTED_TARGETS} FILE gpslam-exports.cmake)\n\n"
  },
  {
    "path": "LICENSE",
    "content": "Copyright (c) 2016, Georgia Tech Research Corporation\nAtlanta, Georgia 30332-0415\nAll Rights Reserved\n\nRedistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:\n\n1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.\n\n2. 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.\n\n3. 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.\n\nTHIS 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.\n"
  },
  {
    "path": "README.md",
    "content": "GP-SLAM\n===================================================\nGP-SLAM is a library implenmenting sparse Gaussian process (GP) regression for continuous-time trajectory estimation and mapping. The core library is developed by C++ language, and an optional Matlab toolbox is also provided. Examples are provided in Matlab scripts.\n\nGP-SLAM is being developed by [Jing Dong](mailto:thu.dongjing@gmail.com) and [Xinyan Yan](mailto:voidpointeryan@gmail.com) as part of their work at Georgia Tech Robot Learning Lab. \n\nPrerequisites\n------\n\n- CMake >= 2.6 (Ubuntu: `sudo apt-get install cmake`), compilation configuration tool.\n- [Boost](http://www.boost.org/) >= 1.46 (Ubuntu: `sudo apt-get install libboost-all-dev`), portable C++ source libraries.\n- [GTSAM](https://bitbucket.org/gtborg/gtsam) >= 4.0 alpha, a C++ library that implement smoothing and mapping (SAM) in robotics and vision.\n\nCompilation & Installation\n------\n\nIn the library folder excute:\n\n```\n$ mkdir build\n$ cd build\n$ cmake ..\n$ make check  # optonal, run unit tests\n$ make install\n```\n\nMatlab Toolbox\n-----\n\nAn optional Matlab toolbox is provided to use our library in Matlab. To enable Matlab toolbox during compilation:\n\n```\n$ cmake -DGPSLAM_BUILD_MATLAB_TOOLBOX:OPTION=ON -DGTSAM_TOOLBOX_INSTALL_PATH:PATH=/path/install/toolbox ..\n$ make install\n```\n\nAfter you install the Matlab toolbox, don't forget to add your `/path/install/toolbox` to your Matlab path.\n\nCompatibility\n-----\n\nThe GP-SLAM library is designed to be cross-platform, but it has been only tested on Ubuntu Linux for now.\n\nTested Compilers: \n\n- GCC 4.8, 5.4\n\nTested Boost version: 1.48-1.61\n\nLinking to External Projects\n-----\n\nWe provide easy linking to external **CMake** projects. Add following lines to your CMakeLists.txt\n\n```\nfind_package(gpslam REQUIRED)\ninclude_directories(${gpslam_INCLUDE_DIR})\n```\n\nQuestions & Bug reporting\n-----\n\nPlease use Github issue tracker to report bugs. For other questions please contact [Jing Dong](mailto:thu.dongjing@gmail.com).\n\n\nCiting\n-----\n\nIf you use GP-SLAM in an academic context, please cite following publications:\n\n```\n@inproceedings{Yan17ras,  \n  Author = \"Xinyan Yan and Vadim Indelman and Byron Boots\",\n  journal = \" Robotics and Autonomous Systems\",\n  Title = \"Incremental Sparse {GP} Regression for Continuous-time Trajectory Estimation and Mapping\",\n  Year = {2017},\n  pages=\"120-132\",\n  volume = {87}\n}\n@article{Dong17arxiv,\n  author    = {Jing Dong and Byron Boots and Frank Dellaert},\n  title     = {Sparse Gaussian Processes for Continuous-Time Trajectory Estimation on Matrix Lie Groups},\n  journal   = {Arxiv},\n  volume    = {abs/1705.06020},\n  year      = {2017},\n  url       = {http://arxiv.org/abs/1705.06020}\n}\n```\n\n\nLicense\n-----\n\nGP-SLAM is released under the BSD license, reproduced in the file LICENSE in this directory.\n"
  },
  {
    "path": "gpslam/CMakeLists.txt",
    "content": "# We split the library in to separate subfolders, each containing\n# tests, timing, and an optional convenience library.\n# The following variable is the master list of subdirs to add\nset(gpslam_subdirs \n    gp \n    slam \n)\nset(gpslam_srcs)\n\n# files want to be excluded\nset(excluded_sources \"\")\n\n\n# Library sources\nforeach(subdir ${gpslam_subdirs})\n    file(GLOB subdir_srcs \"${subdir}/*.cpp\" \"${subdir}/*.h\")\n    list(REMOVE_ITEM subdir_srcs \"${excluded_sources}\")\n\n    file(GLOB subdir_test_files \"${subdir}/tests/*\")\n  \n    list(APPEND gpslam_srcs ${subdir_srcs})\n    message(STATUS \"Building Module: ${subdir}\")\n\n    # local and tests\n    add_subdirectory(${subdir})\nendforeach(subdir)\n\n\n# build shared lib\nadd_library(${PROJECT_NAME} SHARED ${gpslam_srcs})\ntarget_link_libraries(${PROJECT_NAME} ${Boost_LIBRARIES} ${GTSAM_LIBS})\n\n# Install library\ninstall(TARGETS ${PROJECT_NAME} EXPORT gpslam-exports LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin)\n\n\n"
  },
  {
    "path": "gpslam/gp/CMakeLists.txt",
    "content": "# Install headers\nfile(GLOB gp_headers \"*.h\")\ninstall(FILES ${gp_headers} DESTINATION include/gpslam/gp)\n\n# Build tests\ngtsamAddTestsGlob(gp \"tests/*.cpp\" \"\" ${PROJECT_NAME})\n"
  },
  {
    "path": "gpslam/gp/GPutils.cpp",
    "content": "/**\n *  @file  GPutils.cpp\n *  @brief GP utils, calculation of Qc, Q, Lamda matrices etc.\n *  @author Xinyan Yan, Jing Dong\n *  @date Qct 26, 2015\n **/\n\n#include <gpslam/gp/GPutils.h>\n\nusing namespace gtsam;\n\n\nnamespace gpslam {\n\n/* ************************************************************************** */\nMatrix getQc(const SharedNoiseModel& Qc_model) {\n  noiseModel::Gaussian *Gassian_model =\n      dynamic_cast<noiseModel::Gaussian*>(Qc_model.get());\n  return (Gassian_model->R().transpose() * Gassian_model->R()).inverse();\n}\n\n} // namespace gtsam\n\n\n"
  },
  {
    "path": "gpslam/gp/GPutils.h",
    "content": "/**\n *  @file  GPutils.h\n *  @brief GP utils, calculation of Qc, Q, Lamda matrices etc.\n *  @author Xinyan Yan, Jing Dong\n *  @date Qct 26, 2015\n **/\n\n#pragma once\n\n#include <gtsam/linear/NoiseModel.h>\n#include <gtsam/base/Vector.h>\n#include <gtsam/base/Matrix.h>\n\n#include <cmath>\n\n\nnamespace gpslam {\n\n/// get Qc covariance matrix from noise model\ngtsam::Matrix getQc(const gtsam::SharedNoiseModel& Qc_model);\n\n\n/// calculate Q\ntemplate <int Dim>\nEigen::Matrix<double, 2*Dim, 2*Dim> calcQ(const Eigen::Matrix<double, Dim, Dim>& Qc, double tau) {\n  Eigen::Matrix<double, 2*Dim, 2*Dim> Q = (Eigen::Matrix<double, 2*Dim, 2*Dim>() <<\n      1.0 / 3 * pow(tau, 3.0) * Qc, 1.0 / 2 * pow(tau, 2.0) * Qc,\n      1.0 / 2 * pow(tau, 2.0) * Qc, tau * Qc).finished();\n  return Q;\n}\n\n/// calculate Q_inv\ntemplate <int Dim>\nEigen::Matrix<double, 2*Dim, 2*Dim> calcQ_inv(const Eigen::Matrix<double, Dim, Dim>& Qc, double tau) {\n  Eigen::Matrix<double, Dim, Dim> Qc_inv = Qc.inverse();\n  Eigen::Matrix<double, 2*Dim, 2*Dim> Q_inv =\n      (Eigen::Matrix<double, 2*Dim, 2*Dim>() <<\n          12.0 * pow(tau, -3.0) * Qc_inv, (-6.0) * pow(tau, -2.0) * Qc_inv,\n          (-6.0) * pow(tau, -2.0) * Qc_inv, 4.0 * pow(tau, -1.0) * Qc_inv).finished();\n  return Q_inv;\n}\n\n/// calculate Phi\ntemplate <int Dim>\nEigen::Matrix<double, 2*Dim, 2*Dim> calcPhi(double tau) {\n\n  Eigen::Matrix<double, 2*Dim, 2*Dim> Phi = (Eigen::Matrix<double, 2*Dim, 2*Dim>() <<\n      Eigen::Matrix<double, Dim, Dim>::Identity(), tau * Eigen::Matrix<double, Dim, Dim>::Identity(),\n      Eigen::Matrix<double, Dim, Dim>::Zero(), Eigen::Matrix<double, Dim, Dim>::Identity()).finished();\n  return Phi;\n}\n\n/// calculate Lambda\ntemplate <int Dim>\nEigen::Matrix<double, 2*Dim, 2*Dim> calcLambda(const Eigen::Matrix<double, Dim, Dim>& Qc,\n    double delta_t, const double tau) {\n\n  Eigen::Matrix<double, 2*Dim, 2*Dim> Lambda = calcPhi<Dim>(tau) - calcQ(Qc, tau) * (calcPhi<Dim>(delta_t - tau).transpose())\n    * calcQ_inv(Qc, delta_t) * calcPhi<Dim>(delta_t);\n  return Lambda;\n}\n\n/// calculate Psi\ntemplate <int Dim>\nEigen::Matrix<double, 2*Dim, 2*Dim> calcPsi(const Eigen::Matrix<double, Dim, Dim>& Qc,\n    double delta_t, double tau) {\n\n  Eigen::Matrix<double, 2*Dim, 2*Dim> Psi = calcQ(Qc, tau) * (calcPhi<Dim>(delta_t - tau).transpose())\n    * calcQ_inv(Qc, delta_t);\n  return Psi;\n}\n\n} // namespace gtsam\n\n"
  },
  {
    "path": "gpslam/gp/GaussianProcessInterpolatorLinear.h",
    "content": "/**\n * @file GaussianProcessInterpolatorLinear.h\n * @brief Base and utils for Gaussian Process Interpolated measurement factor, linear version\n * @author Jing Dong, Xinyan Yan\n * @date Oct 26, 2015\n */\n\n#pragma once\n\n#include <gpslam/gp/GPutils.h>\n\n#include <gtsam/base/OptionalJacobian.h>\n#include <gtsam/base/Matrix.h>\n\n#include <boost/serialization/array.hpp>\n\n\nnamespace gpslam {\n\n/**\n * 4-way factor for Gaussian Process interpolator, linear version\n * interpolate pose and velocity given consecutive poses and velocities\n */\ntemplate <int Dim>\nclass GaussianProcessInterpolatorLinear {\n\nprivate:\n  typedef GaussianProcessInterpolatorLinear<Dim> This;\n  typedef Eigen::Matrix<double, Dim, 1> VectorDim;\n  typedef Eigen::Matrix<double, 2*Dim, 1> Vector2Dim;\n  typedef Eigen::Matrix<double, Dim, Dim> MatrixDim;\n  typedef Eigen::Matrix<double, 2*Dim, 2*Dim> Matrix2Dim;\n\n  double delta_t_;\t\t// t_{i+1} - t_i\n  double tau_;\t\t\t// tau - t_i. we use tau as time interval from t_i instead of from t_0 as in Barfoot papers\n\n  MatrixDim Qc_;\n  Matrix2Dim Lambda_;\n  Matrix2Dim Psi_;\n\npublic:\n\n  /// Default constructor: only for serialization\n  GaussianProcessInterpolatorLinear() {}\n\n  /**\n   * Constructor\n   * @param Qc noise model of Qc\n   * @param delta_t the time between the two states\n   * @param tau the time of interval status\n   */\n  GaussianProcessInterpolatorLinear(const gtsam::SharedNoiseModel& Qc_model,\n      double delta_t, double tau) :\n      delta_t_(delta_t), tau_(tau) {\n\n    // check noise model dim\n    assert(Qc_model->dim() == Dim);\n\n    // Calcuate Lambda and Psi\n    Qc_ = getQc(Qc_model);\n    Lambda_ = calcLambda(Qc_, delta_t_, tau_);\n    Psi_ = calcPsi(Qc_, delta_t_, tau_);\n  }\n\n  /** Virtual destructor */\n  virtual ~GaussianProcessInterpolatorLinear() {}\n\n\n  /// interpolate pose with Jacobians\n  VectorDim interpolatePose(\n      const VectorDim& pose1, const VectorDim& vel1,\n      const VectorDim& pose2, const VectorDim& vel2,\n      gtsam::OptionalJacobian<Dim, Dim> H1 = boost::none,\n      gtsam::OptionalJacobian<Dim, Dim> H2 = boost::none,\n      gtsam::OptionalJacobian<Dim, Dim> H3 = boost::none,\n      gtsam::OptionalJacobian<Dim, Dim> H4 = boost::none) const {\n\n    // state vector\n    Vector2Dim x1 = (Vector2Dim() << pose1, vel1).finished();\n    Vector2Dim x2 = (Vector2Dim() << pose2, vel2).finished();\n\n    // jacobians\n    if (H1) *H1 = Lambda_.template block<Dim,Dim>(0, 0);\n    if (H2) *H2 = Lambda_.template block<Dim,Dim>(0, Dim);\n    if (H3) *H3 = Psi_.template block<Dim,Dim>(0, 0);\n    if (H4) *H4 = Psi_.template block<Dim,Dim>(0, Dim);\n\n    // interpolate pose (just calculate upper part of the interpolated state vector to save time)\n    return Lambda_.template block<Dim,2*Dim>(0, 0) * x1 + Psi_.template block<Dim,2*Dim>(0, 0) * x2;\n  }\n\n\n  /// update jacobian based on interpolated jacobians\n  static void updatePoseJacobians(const gtsam::Matrix& Hpose,  const gtsam::Matrix& Hint1,\n      const gtsam::Matrix& Hint2, const gtsam::Matrix& Hint3, const gtsam::Matrix& Hint4,\n      boost::optional<gtsam::Matrix&> H1, boost::optional<gtsam::Matrix&> H2,\n      boost::optional<gtsam::Matrix&> H3, boost::optional<gtsam::Matrix&> H4) {\n    if (H1) *H1 = Hpose * Hint1;\n    if (H2) *H2 = Hpose * Hint2;\n    if (H3) *H3 = Hpose * Hint3;\n    if (H4) *H4 = Hpose * Hint4;\n  }\n\n\n  /// interpolate velocity with Jacobians\n  VectorDim interpolateVelocity(\n      const VectorDim& pose1, const VectorDim& vel1,\n      const VectorDim& pose2, const VectorDim& vel2,\n      gtsam::OptionalJacobian<Dim, Dim> H1 = boost::none,\n      gtsam::OptionalJacobian<Dim, Dim> H2 = boost::none,\n      gtsam::OptionalJacobian<Dim, Dim> H3 = boost::none,\n      gtsam::OptionalJacobian<Dim, Dim> H4 = boost::none) const {\n\n    // state vector\n    Vector2Dim x1 = (Vector2Dim() << pose1, vel1).finished();\n    Vector2Dim x2 = (Vector2Dim() << pose2, vel2).finished();\n\n    // jacobians\n    if (H1) *H1 = Lambda_.template block<Dim,Dim>(Dim, 0);\n    if (H2) *H2 = Lambda_.template block<Dim,Dim>(Dim, Dim);\n    if (H3) *H3 = Psi_.template block<Dim,Dim>(Dim, 0);\n    if (H4) *H4 = Psi_.template block<Dim,Dim>(Dim, Dim);\n\n    // interpolate pose (just calculate lower part of the interpolated state vector to save time)\n    return Lambda_.template block<Dim,2*Dim>(Dim, 0) * x1 + Psi_.template block<Dim,2*Dim>(Dim, 0) * x2;\n  }\n\n  /** demensions */\n  size_t dim() const { return Dim; }\n\n\n  /**\n   * Testables\n   */\n\n  /** equals specialized to this factor */\n  virtual bool equals(const This& expected, double tol=1e-9) const {\n    return fabs(this->delta_t_ - expected.delta_t_) < tol &&\n        fabs(this->tau_ - expected.tau_) < tol &&\n        gtsam::equal_with_abs_tol(this->Qc_, expected.Qc_, tol) &&\n        gtsam::equal_with_abs_tol(this->Lambda_, expected.Lambda_, tol) &&\n        gtsam::equal_with_abs_tol(this->Psi_, expected.Psi_, tol);\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\") const {\n    std::cout << s << \"GaussianProcessInterpolatorLinear<\" << Dim << \">\" << std::endl;\n    std::cout << \"delta_t = \" << delta_t_ << \", tau = \" << tau_ << std::endl;\n    //std::cout << \"Qc = \" << Qc_ << std::endl;\n  }\n\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_NVP(delta_t_);\n    ar & BOOST_SERIALIZATION_NVP(tau_);\n    using namespace boost::serialization;\n    ar & make_nvp(\"Qc\", make_array(Qc_.data(), Qc_.size()));\n    ar & make_nvp(\"Lambda\", make_array(Lambda_.data(), Lambda_.size()));\n    ar & make_nvp(\"Psi\", make_array(Psi_.data(), Psi_.size()));\n  }\n};\n\n} // \\ namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<int Dim>\nstruct traits<gpslam::GaussianProcessInterpolatorLinear<Dim> > : public Testable<\n    gpslam::GaussianProcessInterpolatorLinear<Dim> > {};\n}\n\n"
  },
  {
    "path": "gpslam/gp/GaussianProcessInterpolatorPose2.h",
    "content": "/**\n * @file GaussianProcessInterpolatorPose2.h\n * @brief Base and utils for Gaussian Process Interpolated measurement factor, works only in SE(2)\n * @author Jing Dong\n */\n\n#pragma once\n\n#include <gpslam/gp/GPutils.h>\n\n#include <gtsam/geometry/Pose2.h>\n#include <gtsam/base/Matrix.h>\n\n\nnamespace gpslam {\n\n/**\n * 4-way factor for Gaussian Process interpolator, SE(2) version\n * interpolate pose and velocity given consecutive poses and velocities\n */\nclass GaussianProcessInterpolatorPose2 {\n\nprivate:\n  typedef GaussianProcessInterpolatorPose2 This;\n  double delta_t_;\t\t// t_{i+1} - t_i\n  double tau_;\t\t\t// tau - t_i. we use tau as time interval from t_i instead of from t_0 as in Barfoot papers\n  gtsam::Matrix3 Qc_;\n  gtsam::Matrix6 Lambda_;\n  gtsam::Matrix6 Psi_;\n\npublic:\n\n  /// Default constructor: only for serialization\n  GaussianProcessInterpolatorPose2() {}\n\n  /**\n   * Constructor\n   * @param Qc noise model of Qc\n   * @param delta_t the time between the two states\n   * @param tau the time of interval status\n   */\n  GaussianProcessInterpolatorPose2(const gtsam::SharedNoiseModel& Qc_model, double delta_t, double tau) :\n      delta_t_(delta_t), tau_(tau) {\n\n    // Calcuate Lambda and Psi\n    Qc_ = getQc(Qc_model);\n    Lambda_ = calcLambda(Qc_, delta_t_, tau_);\n    Psi_ = calcPsi(Qc_, delta_t_, tau_);\n  }\n\n  /** Virtual destructor */\n  virtual ~GaussianProcessInterpolatorPose2() {}\n\n\n  /// interpolate pose with Jacobians\n  gtsam::Pose2 interpolatePose(\n      const gtsam::Pose2& pose1, const gtsam::Vector3& vel1,\n      const gtsam::Pose2& pose2, const gtsam::Vector3& vel2,\n      gtsam::OptionalJacobian<3, 3> H1 = boost::none,\n      gtsam::OptionalJacobian<3, 3> H2 = boost::none,\n      gtsam::OptionalJacobian<3, 3> H3 = boost::none,\n      gtsam::OptionalJacobian<3, 3> H4 = boost::none) const {\n\n    using namespace gtsam;\n\n    const Vector6 r1 = (Vector6() << Vector3::Zero(), vel1).finished();\n    Matrix3 Hinv, Hcomp11, Hcomp12, Hlogmap;\n    Vector3 r;\n    if (H1 || H2 || H3 || H4)\n      r = Pose2::Logmap(pose1.inverse(Hinv).compose(pose2, Hcomp11, Hcomp12), Hlogmap);\n    else\n      r = Pose2::Logmap(pose1.inverse().compose(pose2));\n    const Vector6 r2 = (Vector6() << r, vel2).finished();\n\n    Pose2 pose;\n    if (H1 || H2 || H3 || H4) {\n      Matrix3 Hcomp21, Hcomp22, Hexp;\n      pose = pose1.compose(Pose2::Expmap(Lambda_.block<3, 6>(0, 0) * r1 + Psi_.block<3, 6>(0, 0) * r2, Hexp), Hcomp21, Hcomp22);\n      Matrix3 Hexpr1 = Hcomp22*Hexp;\n      if (H1) *H1 = Hcomp21 + Hexpr1*Psi_.block<3, 3>(0, 0)*Hlogmap*Hcomp11*Hinv;\n      if (H2) *H2 = Hexpr1*Lambda_.block<3, 3>(0, 3);\n      if (H3) *H3 = Hexpr1*Psi_.block<3, 3>(0, 0)*Hlogmap*Hcomp12;\n      if (H4) *H4 = Hexpr1*Psi_.block<3, 3>(0, 3);\n    } else {\n      pose = pose1.compose(Pose2::Expmap(Lambda_.block<3, 6>(0, 0) * r1 + Psi_.block<3, 6>(0, 0) * r2));\n    }\n\n    return pose;\n  }\n\n  /// update jacobian based on interpolated jacobians\n  static void updatePoseJacobians(const gtsam::Matrix& Hpose,  const gtsam::Matrix& Hint1,\n      const gtsam::Matrix& Hint2, const gtsam::Matrix& Hint3, const gtsam::Matrix& Hint4,\n      boost::optional<gtsam::Matrix&> H1, boost::optional<gtsam::Matrix&> H2,\n      boost::optional<gtsam::Matrix&> H3, boost::optional<gtsam::Matrix&> H4) {\n    if (H1) *H1 = Hpose * Hint1;\n    if (H2) *H2 = Hpose * Hint2;\n    if (H3) *H3 = Hpose * Hint3;\n    if (H4) *H4 = Hpose * Hint4;\n  }\n\n  /// interpolate velocity with Jacobians\n  /// TODO: implementation\n  gtsam::Vector3 interpolateVelocity(\n      const gtsam::Pose2& pose1, const gtsam::Vector3& vel1,\n      const gtsam::Pose2& pose2, const gtsam::Vector3& vel2,\n      gtsam::OptionalJacobian<3, 3> H1 = boost::none,\n      gtsam::OptionalJacobian<3, 3> H2 = boost::none,\n      gtsam::OptionalJacobian<3, 3> H3 = boost::none,\n      gtsam::OptionalJacobian<3, 3> H4 = boost::none) const ;\n\n\n  /**\n   * Testables\n   */\n\n  /** equals specialized to this factor */\n  virtual bool equals(const This& expected, double tol=1e-9) const {\n    return fabs(this->delta_t_ - expected.delta_t_) < tol &&\n        fabs(this->tau_ - expected.tau_) < tol &&\n        gtsam::equal_with_abs_tol(this->Qc_, expected.Qc_, tol) &&\n        gtsam::equal_with_abs_tol(this->Lambda_, expected.Lambda_, tol) &&\n        gtsam::equal_with_abs_tol(this->Psi_, expected.Psi_, tol);\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\") const {\n    std::cout << s << \"GaussianProcessInterpolatorPose2\" << std::endl;\n    std::cout << \"delta_t = \" << delta_t_ << \", tau = \" << tau_ << std::endl;\n    //std::cout << \"Qc = \" << Qc_ << std::endl;\n  }\n\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_NVP(delta_t_);\n    ar & BOOST_SERIALIZATION_NVP(tau_);\n    using namespace boost::serialization;\n    ar & make_nvp(\"Qc\", make_array(Qc_.data(), Qc_.size()));\n    ar & make_nvp(\"Lambda\", make_array(Lambda_.data(), Lambda_.size()));\n    ar & make_nvp(\"Psi\", make_array(Psi_.data(), Psi_.size()));\n  }\n};\n\n} // \\ namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GaussianProcessInterpolatorPose2> : public Testable<\n    gpslam::GaussianProcessInterpolatorPose2> {};\n}\n"
  },
  {
    "path": "gpslam/gp/GaussianProcessInterpolatorPose3.h",
    "content": "/**\n * @file GaussianProcessInterpolatorPose3.h\n * @brief Base and utils for Gaussian Process Interpolated measurement factor, SE(3) version\n * @author Jing Dong, Xinyan Yan\n */\n\n#pragma once\n\n#include <gpslam/gp/GPutils.h>\n#include <gpslam/gp/Pose3utils.h>\n\n#include <gtsam/geometry/Pose3.h>\n#include <gtsam/base/Matrix.h>\n\n\nnamespace gpslam {\n\n/**\n * 4-way factor for Gaussian Process interpolator, SE(3) version\n * interpolate pose and velocity given consecutive poses and velocities\n */\nclass GaussianProcessInterpolatorPose3 {\n\nprivate:\n  typedef GaussianProcessInterpolatorPose3 This;\n  double delta_t_;\t\t// t_{i+1} - t_i\n  double tau_;\t\t\t// tau - t_i. we use tau as time interval from t_i instead of from t_0 as in Barfoot papers\n  gtsam::Matrix6 Qc_;\n  Matrix_12 Lambda_;\n  Matrix_12 Psi_;\n\npublic:\n\n  /// Default constructor: only for serialization\n  GaussianProcessInterpolatorPose3() {}\n\n  /**\n   * Constructor\n   * @param Qc noise model of Qc\n   * @param delta_t the time between the two states\n   * @param tau the time of interval status\n   */\n  GaussianProcessInterpolatorPose3(const gtsam::SharedNoiseModel& Qc_model, double delta_t, double tau) :\n      delta_t_(delta_t), tau_(tau) {\n\n    // Calcuate Lambda and Psi\n    Qc_ = getQc(Qc_model);\n    Lambda_ = calcLambda(Qc_, delta_t_, tau_);\n    Psi_ = calcPsi(Qc_, delta_t_, tau_);\n  }\n\n  /** Virtual destructor */\n  virtual ~GaussianProcessInterpolatorPose3() {}\n\n\n  /// interpolate pose with Jacobians\n  gtsam::Pose3 interpolatePose(const gtsam::Pose3& pose1, const gtsam::Vector6& vel1,\n      const gtsam::Pose3& pose2, const gtsam::Vector6& vel2,\n      gtsam::OptionalJacobian<6, 6> H1 = boost::none, gtsam::OptionalJacobian<6, 6> H2 = boost::none,\n      gtsam::OptionalJacobian<6, 6> H3 = boost::none, gtsam::OptionalJacobian<6, 6> H4 = boost::none) const {\n\n    using namespace gtsam;\n\n    const Vector_12 r1 = (Vector_12() << Vector6::Zero(), vel1).finished();\n    Matrix6 Hinv, Hcomp11, Hcomp12, Hlogmap;\n    Vector6 r;\n    if (H1 || H2 || H3 || H4)\n      r = Pose3::Logmap(pose1.inverse(Hinv).compose(pose2, Hcomp11, Hcomp12), Hlogmap);\n    else\n      r = Pose3::Logmap(pose1.inverse().compose(pose2));\n\n    const Matrix6 Jinv = rightJacobianPose3inv(r);\n    const Vector_12 r2 = (Vector_12() << r, Jinv * vel2).finished();\n\n    Pose3 pose;\n\n    if (H1 || H2 || H3 || H4) {\n      Matrix6 Hcomp21, Hcomp22, Hexp;\n      pose = pose1.compose(Pose3::Expmap(Lambda_.block<6, 12>(0, 0) * r1 + Psi_.block<6, 12>(0, 0) * r2, Hexp), Hcomp21, Hcomp22);\n      Matrix6 Hexpr1 = Hcomp22*Hexp;\n\n      if (H1) {\n        const Matrix6 tmp = Hlogmap * Hcomp11 * Hinv;\n        const Matrix_12_6 dr2_dT1 = (Matrix_12_6() << tmp, jacobianMethodNumercialDiff(\n            rightJacobianPose3inv, r, vel2) * tmp).finished();\n        *H1 = Hcomp21 + Hexpr1*Psi_.block<6, 12>(0, 0)*dr2_dT1;\n      }\n\n      if (H2) *H2 = Hexpr1*Lambda_.block<6, 6>(0, 6);\n\n      if (H3) {\n        const Matrix6 tmp = Hlogmap * Hcomp12;\n        const Matrix_12_6 dr2_dT2 = (Matrix_12_6() << tmp, jacobianMethodNumercialDiff(\n            rightJacobianPose3inv, r, vel2) * tmp).finished();\n        *H3 = Hexpr1*Psi_.block<6, 12>(0, 0)*dr2_dT2;\n      }\n\n      if (H4) *H4 = Hexpr1*Psi_.block<6, 6>(0, 6) * Jinv;\n\n    } else {\n      pose = pose1.compose(Pose3::Expmap(Lambda_.block<6, 12>(0, 0) * r1 + Psi_.block<6, 12>(0, 0) * r2));\n    }\n\n    return pose;\n  }\n\n  /// update jacobian based on interpolated jacobians\n  static void updatePoseJacobians(const gtsam::Matrix& Hpose,  const gtsam::Matrix& Hint1,\n      const gtsam::Matrix& Hint2, const gtsam::Matrix& Hint3, const gtsam::Matrix& Hint4,\n      boost::optional<gtsam::Matrix&> H1, boost::optional<gtsam::Matrix&> H2,\n      boost::optional<gtsam::Matrix&> H3, boost::optional<gtsam::Matrix&> H4) {\n    if (H1) *H1 = Hpose * Hint1;\n    if (H2) *H2 = Hpose * Hint2;\n    if (H3) *H3 = Hpose * Hint3;\n    if (H4) *H4 = Hpose * Hint4;\n  }\n\n  /// interpolate velocity with Jacobians\n  /// TODO: implementation\n  gtsam::Pose3 interpolateVelocity(const gtsam::Pose3& pose1, const gtsam::Vector6& vel1,\n      const gtsam::Pose3& pose2, const gtsam::Vector6& vel2,\n      gtsam::OptionalJacobian<6, 6> H1 = boost::none, gtsam::OptionalJacobian<6, 6> H2 = boost::none,\n      gtsam::OptionalJacobian<6, 6> H3 = boost::none, gtsam::OptionalJacobian<6, 6> H4 = boost::none) const ;\n\n\n  /**\n   * Testables\n   */\n\n  /** equals specialized to this factor */\n  virtual bool equals(const This& expected, double tol=1e-9) const {\n    return fabs(this->delta_t_ - expected.delta_t_) < tol &&\n        fabs(this->tau_ - expected.tau_) < tol &&\n        gtsam::equal_with_abs_tol(this->Qc_, expected.Qc_, tol) &&\n        gtsam::equal_with_abs_tol(this->Lambda_, expected.Lambda_, tol) &&\n        gtsam::equal_with_abs_tol(this->Psi_, expected.Psi_, tol);\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\") const {\n    std::cout << s << \"GaussianProcessInterpolatorPose3\" << std::endl;\n    std::cout << \"delta_t = \" << delta_t_ << \", tau = \" << tau_ << std::endl;\n    //std::cout << \"Qc = \" << Qc_ << std::endl;\n  }\n\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_NVP(delta_t_);\n    ar & BOOST_SERIALIZATION_NVP(tau_);\n    using namespace boost::serialization;\n    ar & make_nvp(\"Qc\", make_array(Qc_.data(), Qc_.size()));\n    ar & make_nvp(\"Lambda\", make_array(Lambda_.data(), Lambda_.size()));\n    ar & make_nvp(\"Psi\", make_array(Psi_.data(), Psi_.size()));\n  }\n};\n\n} // \\ namespace gpslam\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GaussianProcessInterpolatorPose3> : public Testable<\n    gpslam::GaussianProcessInterpolatorPose3> {};\n}\n"
  },
  {
    "path": "gpslam/gp/GaussianProcessInterpolatorPose3VW.h",
    "content": "/**\n * @file GaussianProcessInterpolatorPose3VW.h\n * @brief Base and utils for Gaussian Process Interpolated measurement factor, SE(3). use V/W velocity representation\n * @author Jing Dong, Xinyan Yan\n */\n\n#pragma once\n\n#include <gpslam/gp/GPutils.h>\n#include <gpslam/gp/Pose3utils.h>\n\n#include <gtsam/geometry/Pose3.h>\n#include <gtsam/base/Matrix.h>\n\n\nnamespace gpslam {\n\n/**\n * 4-way factor for Gaussian Process interpolator, SE(3) version\n * 6-DOF velocity is represented by 3-DOF translational and 3-DOF rotational velocities (in body frame).\n * interpolate pose and velocity given consecutive poses and velocities\n */\nclass GaussianProcessInterpolatorPose3VW {\n\nprivate:\n  typedef GaussianProcessInterpolatorPose3VW This;\n  double delta_t_;\t\t// t_{i+1} - t_i\n  double tau_;\t\t\t// tau - t_i. we use tau as time interval from t_i instead of from t_0 as in Barfoot papers\n  gtsam::Matrix6 Qc_;\n  Matrix_12 Lambda_;\n  Matrix_12 Psi_;\n\npublic:\n\n  /// Default constructor: only for serialization\n  GaussianProcessInterpolatorPose3VW() {}\n\n  /**\n   * Constructor\n   * @param Qc noise model of Qc\n   * @param delta_t the time between the two states\n   * @param tau the time of interval status\n   */\n  GaussianProcessInterpolatorPose3VW(const gtsam::SharedNoiseModel& Qc_model, double delta_t, double tau) :\n      delta_t_(delta_t), tau_(tau) {\n\n    // Calcuate Lambda and Psi\n    Qc_ = getQc(Qc_model);\n    Lambda_ = calcLambda(Qc_, delta_t_, tau_);\n    Psi_ = calcPsi(Qc_, delta_t_, tau_);\n  }\n\n  /** Virtual destructor */\n  virtual ~GaussianProcessInterpolatorPose3VW() {}\n\n\n  /// interpolate pose with Jacobians\n  gtsam::Pose3 interpolatePose(\n      const gtsam::Pose3& pose1, const gtsam::Vector3& v1, const gtsam::Vector3& omega1,\n      const gtsam::Pose3& pose2, const gtsam::Vector3& v2, const gtsam::Vector3& omega2,\n      gtsam::OptionalJacobian<6, 6> H1 = boost::none, gtsam::OptionalJacobian<6, 3> H2 = boost::none,\n      gtsam::OptionalJacobian<6, 3> H3 = boost::none, gtsam::OptionalJacobian<6, 6> H4 = boost::none,\n      gtsam::OptionalJacobian<6, 3> H5 = boost::none, gtsam::OptionalJacobian<6, 3> H6 = boost::none) const {\n\n    using namespace gtsam;\n\n    Matrix6 Hinv, Hcomp11, Hcomp12, Hlogmap;\n    Vector6 r;\n    if (H1 || H4)\n      r = Pose3::Logmap(pose1.inverse(Hinv).compose(pose2, Hcomp11, Hcomp12), Hlogmap);\n    else\n      r = Pose3::Logmap(pose1.inverse().compose(pose2));\n\n    const Matrix6 Jinv = rightJacobianPose3inv(r);\n\n    // vel\n    Matrix63 H1v, H1w, H2v, H2w;\n    Matrix6 H1p, H2p;\n    Vector6 vel1, vel2;\n    if (H2 || H3 || H5 || H6) {\n      vel1 = convertVWtoVb(v1, omega1, pose1, H1v, H1w, H1p);\n      vel2 = convertVWtoVb(v2, omega2, pose2, H2v, H2w, H2p);\n    } else {\n      vel1 = convertVWtoVb(v1, omega1, pose1);\n      vel2 = convertVWtoVb(v2, omega2, pose2);\n    }\n    const Vector_12 r1 = (Vector_12() << Vector6::Zero(), vel1).finished();\n    const Vector_12 r2 = (Vector_12() << r, Jinv * vel2).finished();\n\n    // pose\n    Pose3 pose;\n    if (H1 || H2 || H3 || H4) {\n      Matrix6 Hcomp21, Hcomp22, Hexp;\n      pose = pose1.compose(Pose3::Expmap(Lambda_.block<6, 12>(0, 0) * r1 + Psi_.block<6, 12>(0, 0) * r2, Hexp), Hcomp21, Hcomp22);\n      Matrix6 Hexpr1 = Hcomp22*Hexp;\n      Matrix6 Hvel1 = Hexpr1*Lambda_.block<6, 6>(0, 6);\n      Matrix6 Hvel2 = Hexpr1*Psi_.block<6, 6>(0, 6) * Jinv;\n\n      if (H1) {\n        const Matrix6 tmp = Hlogmap * Hcomp11 * Hinv;\n        const Matrix_12_6 dr2_dT1 = (Matrix_12_6() << tmp, jacobianMethodNumercialDiff(\n            rightJacobianPose3inv, r, vel2) * tmp).finished();\n        *H1 = Hcomp21 + Hexpr1*Psi_.block<6, 12>(0, 0)*dr2_dT1 + Hvel1*H1p;\n      }\n\n      if (H2) *H2 = Hvel1 * H1v;\n      if (H3) *H3 = Hvel1 * H1w;\n\n      if (H4) {\n        const Matrix6 tmp = Hlogmap * Hcomp12;\n        const Matrix_12_6 dr2_dT2 = (Matrix_12_6() << tmp, jacobianMethodNumercialDiff(\n            rightJacobianPose3inv, r, vel2) * tmp).finished();\n        *H4 = Hexpr1*Psi_.block<6, 12>(0, 0)*dr2_dT2 + Hvel2*H2p;\n      }\n\n      if (H5) *H5 = Hvel2 * H2v;\n      if (H6) *H6 = Hvel2 * H2w;\n\n    } else {\n      pose = pose1.compose(Pose3::Expmap(Lambda_.block<6, 12>(0, 0) * r1 + Psi_.block<6, 12>(0, 0) * r2));\n    }\n\n    return pose;\n  }\n\n  /// update jacobian based on interpolated jacobians\n  static void updatePoseJacobians(const gtsam::Matrix& Hpose,\n      const gtsam::Matrix& Hint1, const gtsam::Matrix& Hint2, const gtsam::Matrix& Hint3,\n      const gtsam::Matrix& Hint4, const gtsam::Matrix& Hint5, const gtsam::Matrix& Hint6,\n      boost::optional<gtsam::Matrix&> H1, boost::optional<gtsam::Matrix&> H2,\n      boost::optional<gtsam::Matrix&> H3, boost::optional<gtsam::Matrix&> H4,\n      boost::optional<gtsam::Matrix&> H5, boost::optional<gtsam::Matrix&> H6) {\n    if (H1) *H1 = Hpose * Hint1;\n    if (H2) *H2 = Hpose * Hint2;\n    if (H3) *H3 = Hpose * Hint3;\n    if (H4) *H4 = Hpose * Hint4;\n    if (H5) *H5 = Hpose * Hint5;\n    if (H6) *H6 = Hpose * Hint6;\n  }\n\n  /// interpolate velocity with Jacobians\n  /// TODO: implementation\n  gtsam::Vector6 interpolateVelocity(\n      const gtsam::Pose3& pose1, const gtsam::Vector3& v1, const gtsam::Vector3& omega1,\n      const gtsam::Pose3& pose2, const gtsam::Vector3& v2, const gtsam::Vector3& omega2,\n      gtsam::OptionalJacobian<6, 6> H1 = boost::none, gtsam::OptionalJacobian<6, 3> H2 = boost::none,\n      gtsam::OptionalJacobian<6, 3> H3 = boost::none, gtsam::OptionalJacobian<6, 6> H4 = boost::none,\n      gtsam::OptionalJacobian<6, 3> H5 = boost::none, gtsam::OptionalJacobian<6, 3> H6 = boost::none) const ;\n\n\n  /**\n   * Testables\n   */\n\n  /** equals specialized to this factor */\n  virtual bool equals(const This& expected, double tol=1e-9) const {\n    return fabs(this->delta_t_ - expected.delta_t_) < tol &&\n        fabs(this->tau_ - expected.tau_) < tol &&\n        gtsam::equal_with_abs_tol(this->Qc_, expected.Qc_, tol) &&\n        gtsam::equal_with_abs_tol(this->Lambda_, expected.Lambda_, tol) &&\n        gtsam::equal_with_abs_tol(this->Psi_, expected.Psi_, tol);\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\") const {\n    std::cout << s << \"GaussianProcessInterpolatorPose3VW\" << std::endl;\n    std::cout << \"delta_t = \" << delta_t_ << \", tau = \" << tau_ << std::endl;\n    //std::cout << \"Qc = \" << Qc_ << std::endl;\n  }\n\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_NVP(delta_t_);\n    ar & BOOST_SERIALIZATION_NVP(tau_);\n    using namespace boost::serialization;\n    ar & make_nvp(\"Qc\", make_array(Qc_.data(), Qc_.size()));\n    ar & make_nvp(\"Lambda\", make_array(Lambda_.data(), Lambda_.size()));\n    ar & make_nvp(\"Psi\", make_array(Psi_.data(), Psi_.size()));\n  }\n};\n\n} // \\ namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GaussianProcessInterpolatorPose3VW> : public Testable<\n    gpslam::GaussianProcessInterpolatorPose3VW> {};\n}\n"
  },
  {
    "path": "gpslam/gp/GaussianProcessInterpolatorRot3.h",
    "content": "/**\n * @file GaussianProcessInterpolatorRot3.h\n * @brief Base and utils for Gaussian Process Interpolated measurement factor, SO(3) version\n * @author Jing Dong\n */\n\n#pragma once\n\n#include <gpslam/gp/GPutils.h>\n\n#include <gtsam/geometry/Rot3.h>\n#include <gtsam/base/Matrix.h>\n\n\nnamespace gpslam {\n\n/**\n * 4-way factor for Gaussian Process interpolator, SO(3) version\n * interpolate pose and velocity given consecutive poses and velocities\n */\nclass GaussianProcessInterpolatorRot3 {\n\nprivate:\n  typedef GaussianProcessInterpolatorRot3 This;\n  double delta_t_;\t\t// t_{i+1} - t_i\n  double tau_;\t\t\t// tau - t_i. we use tau as time interval from t_i instead of from t_0 as in Barfoot papers\n  gtsam::Matrix3 Qc_;\n  gtsam::Matrix6 Lambda_;\n  gtsam::Matrix6 Psi_;\n\npublic:\n\n  /// Default constructor: only for serialization\n  GaussianProcessInterpolatorRot3() {}\n\n  /**\n   * Constructor\n   * @param Qc noise model of Qc\n   * @param delta_t the time between the two states\n   * @param tau the time of interval status\n   */\n  GaussianProcessInterpolatorRot3(const gtsam::SharedNoiseModel& Qc_model, double delta_t, double tau) :\n      delta_t_(delta_t), tau_(tau) {\n\n    // Calcuate Lambda and Psi\n    Qc_ = getQc(Qc_model);\n    Lambda_ = calcLambda(Qc_, delta_t_, tau_);\n    Psi_ = calcPsi(Qc_, delta_t_, tau_);\n  }\n\n  /** Virtual destructor */\n  virtual ~GaussianProcessInterpolatorRot3() {}\n\n\n  /// interpolate pose with Jacobians\n  gtsam::Rot3 interpolatePose(const gtsam::Rot3& pose1, const gtsam::Vector3& vel1,\n      const gtsam::Rot3& pose2, const gtsam::Vector3& vel2,\n      gtsam::OptionalJacobian<3, 3> H1 = boost::none, gtsam::OptionalJacobian<3, 3> H2 = boost::none,\n      gtsam::OptionalJacobian<3, 3> H3 = boost::none, gtsam::OptionalJacobian<3, 3> H4 = boost::none) const {\n\n    using namespace gtsam;\n\n    const Vector6 r1 = (Vector6() << Vector3::Zero(), vel1).finished();\n    Matrix3 Hinv, Hcomp11, Hcomp12, Hlogmap;\n    Vector3 r;\n    if (H1 || H2 || H3 || H4)\n      r = Rot3::Logmap(pose1.inverse(Hinv).compose(pose2, Hcomp11, Hcomp12), Hlogmap);\n    else\n      r = Rot3::Logmap(pose1.inverse().compose(pose2));\n    const Vector6 r2 = (Vector6() << r, vel2).finished();\n\n    Rot3 pose;\n    if (H1 || H2 || H3 || H4) {\n      Matrix3 Hcomp21, Hcomp22, Hexp;\n      pose = pose1.compose(Rot3::Expmap(Lambda_.block<3, 6>(0, 0) * r1 + Psi_.block<3, 6>(0, 0) * r2, Hexp), Hcomp21, Hcomp22);\n      Matrix3 Hexpr1 = Hcomp22*Hexp;\n      if (H1) *H1 = Hcomp21 + Hexpr1*Psi_.block<3, 3>(0, 0)*Hlogmap*Hcomp11*Hinv;\n      if (H2) *H2 = Hexpr1*Lambda_.block<3, 3>(0, 3);\n      if (H3) *H3 = Hexpr1*Psi_.block<3, 3>(0, 0)*Hlogmap*Hcomp12;\n      if (H4) *H4 = Hexpr1*Psi_.block<3, 3>(0, 3);\n    } else {\n      pose = pose1.compose(Rot3::Expmap(Lambda_.block<3, 6>(0, 0) * r1 + Psi_.block<3, 6>(0, 0) * r2));\n    }\n\n    return pose;\n  }\n\n  /// update jacobian based on interpolated jacobians\n  static void updatePoseJacobians(const gtsam::Matrix& Hpose,  const gtsam::Matrix& Hint1,\n      const gtsam::Matrix& Hint2, const gtsam::Matrix& Hint3, const gtsam::Matrix& Hint4,\n      boost::optional<gtsam::Matrix&> H1, boost::optional<gtsam::Matrix&> H2,\n      boost::optional<gtsam::Matrix&> H3, boost::optional<gtsam::Matrix&> H4) {\n    if (H1) *H1 = Hpose * Hint1;\n    if (H2) *H2 = Hpose * Hint2;\n    if (H3) *H3 = Hpose * Hint3;\n    if (H4) *H4 = Hpose * Hint4;\n  }\n\n  /// interpolate velocity with Jacobians\n  /// TODO: implementation\n  gtsam::Vector3 interpolateVelocity(const gtsam::Rot3& pose1, const gtsam::Vector3& vel1,\n      const gtsam::Rot3& pose2, const gtsam::Vector3& vel2,\n      gtsam::OptionalJacobian<3, 3> H1 = boost::none, gtsam::OptionalJacobian<3, 3> H2 = boost::none,\n      gtsam::OptionalJacobian<3, 3> H3 = boost::none, gtsam::OptionalJacobian<3, 3> H4 = boost::none) const ;\n\n\n  /**\n   * Testables\n   */\n\n  /** equals specialized to this factor */\n  virtual bool equals(const This& expected, double tol=1e-9) const {\n    return fabs(this->delta_t_ - expected.delta_t_) < tol &&\n        fabs(this->tau_ - expected.tau_) < tol &&\n        gtsam::equal_with_abs_tol(this->Qc_, expected.Qc_, tol) &&\n        gtsam::equal_with_abs_tol(this->Lambda_, expected.Lambda_, tol) &&\n        gtsam::equal_with_abs_tol(this->Psi_, expected.Psi_, tol);\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\") const {\n    std::cout << s << \"GaussianProcessInterpolatorRot3\" << std::endl;\n    std::cout << \"delta_t = \" << delta_t_ << \", tau = \" << tau_ << std::endl;\n    //std::cout << \"Qc = \" << Qc_ << std::endl;\n  }\n\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_NVP(delta_t_);\n    ar & BOOST_SERIALIZATION_NVP(tau_);\n    using namespace boost::serialization;\n    ar & make_nvp(\"Qc\", make_array(Qc_.data(), Qc_.size()));\n    ar & make_nvp(\"Lambda\", make_array(Lambda_.data(), Lambda_.size()));\n    ar & make_nvp(\"Psi\", make_array(Psi_.data(), Psi_.size()));\n  }\n};\n\n} // \\ namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GaussianProcessInterpolatorRot3> : public Testable<\n    gpslam::GaussianProcessInterpolatorRot3> {};\n}\n"
  },
  {
    "path": "gpslam/gp/GaussianProcessPriorLinear.h",
    "content": "/**\n *  @file  GaussianProcessPriorLinear.h\n *  @brief Linear GP prior, see Barfoot14rss\n *  @author Xinyan Yan, Jing Dong\n **/\n\n\n#pragma once\n\n#include <gpslam/gp/GPutils.h>\n\n#include <boost/lexical_cast.hpp>\n#include <gtsam/geometry/concepts.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n#include <gtsam/base/Testable.h>\n\n\nnamespace gpslam {\n\n/**\n * 4-way factor for Gaussian Process prior factor, linear version\n */\ntemplate <int Dim>\nclass GaussianProcessPriorLinear: public gtsam::NoiseModelFactor4<\n    Eigen::Matrix<double, Dim, 1>, Eigen::Matrix<double, Dim, 1>,\n    Eigen::Matrix<double, Dim, 1>, Eigen::Matrix<double, Dim, 1> > {\n\nprivate:\n  double delta_t_;\n\n  typedef Eigen::Matrix<double, Dim, 1> VectorDim;\n  typedef Eigen::Matrix<double, 2*Dim, 1> Vector2Dim;\n  typedef Eigen::Matrix<double, Dim, Dim> MatrixDim;\n  typedef Eigen::Matrix<double, 2*Dim, Dim> Matrix21Dim;\n  typedef Eigen::Matrix<double, 2*Dim, 2*Dim> Matrix2Dim;\n  typedef GaussianProcessPriorLinear<Dim> This;\n  typedef gtsam::NoiseModelFactor4<VectorDim, VectorDim, VectorDim, VectorDim> Base;\n\npublic:\n\n  GaussianProcessPriorLinear() {}\t/* Default constructor only for serialization */\n\n  /// Constructor\n  /// @param delta_t is the time between the two states\n  GaussianProcessPriorLinear(gtsam::Key poseKey1, gtsam::Key velKey1,\n      gtsam::Key poseKey2, gtsam::Key velKey2,\n      double delta_t, const gtsam::SharedNoiseModel& Qc_model) :\n        Base(gtsam::noiseModel::Gaussian::Covariance(calcQ<Dim>(getQc(Qc_model), delta_t)),\n        poseKey1, velKey1, poseKey2, velKey2) {\n    delta_t_ = delta_t;\n  }\n\n  virtual ~GaussianProcessPriorLinear() {}\n\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n\n  /// factor error function\n  gtsam::Vector evaluateError(\n      const VectorDim& pose1, const VectorDim& vel1,\n      const VectorDim& pose2, const VectorDim& vel2,\n      boost::optional<gtsam::Matrix&> H1 = boost::none,\n      boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none,\n      boost::optional<gtsam::Matrix&> H4 = boost::none) const {\n\n    // state vector\n    Vector2Dim x1 = (Vector2Dim() << pose1, vel1).finished();\n    Vector2Dim x2 = (Vector2Dim() << pose2, vel2).finished();\n\n    // Jacobians\n    if (H1) *H1 = (Matrix21Dim() << MatrixDim::Identity(),            MatrixDim::Zero()).finished();\n    if (H2) *H2 = (Matrix21Dim() << delta_t_ * MatrixDim::Identity(), MatrixDim::Identity()).finished();\n    if (H3) *H3 = (Matrix21Dim() << -1.0 * MatrixDim::Identity(),     MatrixDim::Zero()).finished();\n    if (H4) *H4 = (Matrix21Dim() << MatrixDim::Zero(),                -1.0 * MatrixDim::Identity()).finished();\n\n    // transition matrix & error\n    return calcPhi<Dim>(delta_t_) * x1 - x2;\n  }\n\n\n  /** demensions */\n  size_t dim() const { return Dim; }\n\n  /** number of variables attached to this factor */\n  size_t size() const {\n    return 4;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e =  dynamic_cast<const This*> (&expected);\n    return e != NULL && Base::equals(*e, tol) && fabs(this->delta_t_ - e->delta_t_) < tol;\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"4-way Gaussian Process Factor Linear<\" << Dim << \">\" << std::endl;\n    Base::print(\"\", keyFormatter);\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(delta_t_);\n  }\n\n}; // GaussianProcessPriorLinear\n\n\n} // namespace gpslam\n\n\n\n/// traits\nnamespace gtsam {\ntemplate<int Dim>\nstruct traits<gpslam::GaussianProcessPriorLinear<Dim> > : public Testable<\n    gpslam::GaussianProcessPriorLinear<Dim> > {};\n}\n"
  },
  {
    "path": "gpslam/gp/GaussianProcessPriorPose2.h",
    "content": "/**\n *  @file  GaussianProcessPriorPose2.h\n *  @brief Pose2 GP prior\n *  @author Jing Dong\n **/\n\n#pragma once\n\n#include <gpslam/gp/GPutils.h>\n\n#include <gtsam/geometry/concepts.h>\n#include <gtsam/geometry/Pose2.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n#include <gtsam/base/Testable.h>\n\n#include <boost/lexical_cast.hpp>\n#include <boost/serialization/export.hpp>\n\n#include <ostream>\n\n\nnamespace gpslam {\n\n/**\n * 4-way factor for Gaussian Process prior factor, SE(2) version\n */\nclass GaussianProcessPriorPose2: public gtsam::NoiseModelFactor4<gtsam::Pose2,\n    gtsam::Vector3, gtsam::Pose2, gtsam::Vector3> {\n\nprivate:\n  double delta_t_;\n  typedef GaussianProcessPriorPose2 This;\n  typedef gtsam::NoiseModelFactor4<gtsam::Pose2, gtsam::Vector3, gtsam::Pose2, gtsam::Vector3> Base;\n\npublic:\n\n  GaussianProcessPriorPose2() {}\t/* Default constructor only for serialization */\n\n  /// Constructor\n  /// @param delta_t is the time between the two states\n  GaussianProcessPriorPose2(gtsam::Key poseKey1, gtsam::Key velKey1,\n      gtsam::Key poseKey2, gtsam::Key velKey2,\n      double delta_t, const gtsam::SharedNoiseModel& Qc_model) :\n    Base(gtsam::noiseModel::Gaussian::Covariance(calcQ<3>(getQc(Qc_model), delta_t)),\n        poseKey1, velKey1, poseKey2, velKey2) {\n    delta_t_ = delta_t;\n  }\n\n  virtual ~GaussianProcessPriorPose2() {}\n\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /// factor error function\n  gtsam::Vector evaluateError(\n      const gtsam::Pose2& pose1, const gtsam::Vector3& vel1,\n      const gtsam::Pose2& pose2, const gtsam::Vector3& vel2,\n      boost::optional<gtsam::Matrix&> H1 = boost::none,\n      boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none,\n      boost::optional<gtsam::Matrix&> H4 = boost::none) const {\n\n    using namespace gtsam;\n\n    Matrix3 Hinv, Hcomp1, Hcomp2, Hlogmap;\n    Vector3 r;\n    if (H1 || H2 || H3 || H4)\n      r = Pose2::Logmap(pose1.inverse(Hinv).compose(pose2, Hcomp1, Hcomp2), Hlogmap);\n    else\n      r = Pose2::Logmap(pose1.inverse().compose(pose2));\n\n    // jacobians\n    if (H1) *H1 = (Matrix63() << Hlogmap * Hcomp1 * Hinv, Matrix3::Zero()).finished();\n    if (H2) *H2 = (Matrix63() << -delta_t_ * Matrix3::Identity(), -Matrix3::Identity()).finished();\n    if (H3) *H3 = (Matrix63() << Hlogmap * Hcomp2, Matrix3::Zero()).finished();\n    if (H4) *H4 = (Matrix63() << Matrix3::Zero(), Matrix3::Identity()).finished();\n\n    return (Vector(6) << (r - vel1 * delta_t_), (vel2 - vel1)).finished();\n  }\n\n  /** number of variables attached to this factor */\n  size_t size() const {\n    return 4;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e =  dynamic_cast<const This*> (&expected);\n    return e != NULL && Base::equals(*e, tol) && fabs(this->delta_t_ - e->delta_t_) < tol;\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"4-way Gaussian Process Factor Pose2\" << std::endl;\n    Base::print(\"\", keyFormatter);\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(delta_t_);\n  }\n\n}; // GaussianProcessPriorPose2\n\n} // namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GaussianProcessPriorPose2> : public Testable<gpslam::GaussianProcessPriorPose2> {};\n}\n"
  },
  {
    "path": "gpslam/gp/GaussianProcessPriorPose3.h",
    "content": "/**\n *  @file  GaussianProcessPriorPose3.h\n *  @brief Pose3 GP prior\n *  @author Xinyan Yan, Jing Dong\n **/\n\n#pragma once\n\n#include <gpslam/gp/GPutils.h>\n#include <gpslam/gp/Pose3utils.h>\n\n#include <gtsam/geometry/concepts.h>\n#include <gtsam/geometry/Pose3.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/Lie.h>\n\n#include <boost/lexical_cast.hpp>\n#include <boost/serialization/export.hpp>\n\n#include <ostream>\n\n\nnamespace gpslam {\n\n/**\n * 4-way factor for Gaussian Process prior factor, SE(3) version\n */\nclass GaussianProcessPriorPose3: public gtsam::NoiseModelFactor4<gtsam::Pose3,\n    gtsam::Vector6, gtsam::Pose3, gtsam::Vector6> {\n\nprivate:\n  double delta_t_;\n  typedef GaussianProcessPriorPose3 This;\n  typedef gtsam::NoiseModelFactor4<gtsam::Pose3, gtsam::Vector6, gtsam::Pose3, gtsam::Vector6> Base;\n\npublic:\n\n  GaussianProcessPriorPose3() {}\t/* Default constructor only for serialization */\n\n  /// Constructor\n  /// @param delta_t is the time between the two states\n  GaussianProcessPriorPose3(gtsam::Key poseKey1, gtsam::Key velKey1,\n      gtsam::Key poseKey2, gtsam::Key velKey2,\n      double delta_t, const gtsam::SharedNoiseModel& Qc_model) :\n    Base(gtsam::noiseModel::Gaussian::Covariance(calcQ<6>(getQc(Qc_model), delta_t)),\n        poseKey1, velKey1, poseKey2, velKey2) {\n    delta_t_ = delta_t;\n  }\n\n  virtual ~GaussianProcessPriorPose3() {}\n\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /// factor error function\n  gtsam::Vector evaluateError(const gtsam::Pose3& pose1, const gtsam::Vector6& vel1,\n      const gtsam::Pose3& pose2, const gtsam::Vector6& vel2,\n      boost::optional<gtsam::Matrix&> H1 = boost::none,\n      boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none,\n      boost::optional<gtsam::Matrix&> H4 = boost::none) const {\n\n    using namespace gtsam;\n\n    Matrix6 Hinv, Hcomp1, Hcomp2, Hlogmap;\n    Vector6 r;\n    if (H1 || H2 || H3 || H4)\n      r = Pose3::Logmap(pose1.inverse(Hinv).compose(pose2, Hcomp1, Hcomp2), Hlogmap);\n    else\n      r = Pose3::Logmap(pose1.inverse().compose(pose2));\n\n    const Matrix6 Jinv = rightJacobianPose3inv(r);\n\n    // jacobians\n    if (H1) {\n      const Matrix6 J_Ti = Hlogmap * Hcomp1 * Hinv;\n      const Matrix6 Jdiff_Ti = jacobianMethodNumercialDiff(rightJacobianPose3inv, r,\n          vel2) * J_Ti;\n      *H1 = (Matrix_12_6() << J_Ti, Jdiff_Ti).finished();\n    }\n\n    if (H2) *H2 = (Matrix_12_6() << -delta_t_ * Matrix6::Identity(), -Matrix6::Identity()).finished();\n\n    if (H3) {\n      const Matrix6 J_Ti1 = Hlogmap * Hcomp2;\n      const Matrix6 Jdiff_Ti1 = jacobianMethodNumercialDiff(rightJacobianPose3inv, r,\n          vel2) * J_Ti1;\n      *H3 = (Matrix_12_6() << J_Ti1, Jdiff_Ti1).finished();\n    }\n\n    if (H4) *H4 = (Matrix_12_6() << Matrix6::Zero(), Jinv).finished();\n\n    return (Vector(12) << (r - vel1 * delta_t_), (Jinv * vel2 - vel1)).finished();\n  }\n\n  /** number of variables attached to this factor */\n  size_t size() const {\n    return 4;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e =  dynamic_cast<const This*> (&expected);\n    return e != NULL && Base::equals(*e, tol) && fabs(this->delta_t_ - e->delta_t_) < tol;\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"4-way Gaussian Process Factor Pose3\" << std::endl;\n    Base::print(\"\", keyFormatter);\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(delta_t_);\n  }\n\n}; // GaussianProcessPriorPose3\n\n\n} // namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GaussianProcessPriorPose3> : public Testable<gpslam::GaussianProcessPriorPose3> {};\n}\n"
  },
  {
    "path": "gpslam/gp/GaussianProcessPriorPose3VW.h",
    "content": "/**\n *  @file  GaussianProcessPriorPose3VW.h\n *  @brief Pose3 GP prior, use V/W velocity representation\n *  @author Xinyan Yan, Jing Dong\n **/\n\n#pragma once\n\n#include <gpslam/gp/GPutils.h>\n#include <gpslam/gp/Pose3utils.h>\n\n#include <gtsam/geometry/concepts.h>\n#include <gtsam/geometry/Pose3.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/Lie.h>\n\n#include <boost/lexical_cast.hpp>\n\n#include <ostream>\n\n\nnamespace gpslam {\n\n/**\n * 4-way factor for Gaussian Process prior factor, SE(3) version\n * 6-DOF velocity is represented by 3-DOF translational and 3-DOF rotational velocities (in body frame).\n */\nclass GaussianProcessPriorPose3VW: public gtsam::NoiseModelFactor6<gtsam::Pose3,\n    gtsam::Vector3, gtsam::Vector3, gtsam::Pose3, gtsam::Vector3, gtsam::Vector3> {\n\nprivate:\n  double delta_t_;\n  typedef GaussianProcessPriorPose3VW This;\n  typedef gtsam::NoiseModelFactor6<gtsam::Pose3, gtsam::Vector3, gtsam::Vector3,\n      gtsam::Pose3, gtsam::Vector3, gtsam::Vector3> Base;\n\npublic:\n\n  GaussianProcessPriorPose3VW() {}\t/* Default constructor only for serialization */\n\n  /// Constructor\n  /// @param delta_t is the time between the two states\n  GaussianProcessPriorPose3VW(\n      gtsam::Key poseKey1, gtsam::Key velKey1, gtsam::Key omegaKey1,\n      gtsam::Key poseKey2, gtsam::Key velKey2, gtsam::Key omegaKey2,\n      double delta_t, const gtsam::SharedNoiseModel& Qc_model) :\n    Base(gtsam::noiseModel::Gaussian::Covariance(calcQ<6>(getQc(Qc_model), delta_t)),\n        poseKey1, velKey1, omegaKey1, poseKey2, velKey2, omegaKey2) {\n    delta_t_ = delta_t;\n  }\n\n  virtual ~GaussianProcessPriorPose3VW() {}\n\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /// factor error function\n  gtsam::Vector evaluateError(\n      const gtsam::Pose3& pose1, const gtsam::Vector3& vel1, const gtsam::Vector3& omega1,\n      const gtsam::Pose3& pose2, const gtsam::Vector3& vel2, const gtsam::Vector3& omega2,\n      boost::optional<gtsam::Matrix&> H1 = boost::none, boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none, boost::optional<gtsam::Matrix&> H4 = boost::none,\n      boost::optional<gtsam::Matrix&> H5 = boost::none, boost::optional<gtsam::Matrix&> H6 = boost::none) const {\n\n    using namespace gtsam;\n\n    Matrix6 Hinv, Hcomp1, Hcomp2, Hlogmap;\n    Vector6 r;\n    if (H1 || H4)\n      r = Pose3::Logmap(pose1.inverse(Hinv).compose(pose2, Hcomp1, Hcomp2), Hlogmap);\n    else\n      r = Pose3::Logmap(pose1.inverse().compose(pose2));\n\n    const Matrix6 Jinv = rightJacobianPose3inv(r);\n\n    // convert body frame velocity to body center\n    Matrix63 H1v, H1w, H2v, H2w;\n    Matrix6 H1p, H2p;\n    Matrix_12_6 Hv1, Hv2;\n    Vector6 v1, v2;\n    if (H2 || H3 || H5 || H6) {\n      v1 = convertVWtoVb(vel1, omega1, pose1, H1v, H1w, H1p);\n      v2 = convertVWtoVb(vel2, omega2, pose2, H2v, H2w, H2p);\n      Hv1 = (Matrix_12_6() << -delta_t_ * Matrix6::Identity(), -Matrix6::Identity()).finished();\n      Hv2 = (Matrix_12_6() << Matrix6::Zero(), Jinv).finished();\n    } else {\n      v1 = convertVWtoVb(vel1, omega1, pose1);\n      v2 = convertVWtoVb(vel2, omega2, pose2);\n    }\n\n    // jacobians\n    if (H1)  {\n      const Matrix6 J_Ti = Hlogmap * Hcomp1 * Hinv;\n      const Matrix6 Jdiff_Ti = jacobianMethodNumercialDiff(rightJacobianPose3inv, r,\n          v2) * J_Ti;\n      *H1 = (Matrix_12_6() << J_Ti-delta_t_*H1p, Jdiff_Ti-H1p).finished();\n    }\n\n    if (H2) *H2 = Hv1 * H1v;\n    if (H3) *H3 = Hv1 * H1w;\n\n    if (H4) {\n      const Matrix6 J_Ti1 = Hlogmap * Hcomp2;\n      const Matrix6 Jdiff_Ti1 = jacobianMethodNumercialDiff(rightJacobianPose3inv, r,\n          v2) * J_Ti1;\n      *H4 = (Matrix_12_6() << J_Ti1, Jdiff_Ti1 + Jinv*H2p).finished();\n    }\n\n    if (H5) *H5 = Hv2 * H2v;\n    if (H6) *H6 = Hv2 * H2w;\n\n    return (Vector(12) << (r - v1 * delta_t_), Jinv * v2 - v1).finished();\n  }\n\n  /** number of variables attached to this factor */\n  size_t size() const {\n    return 6;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e =  dynamic_cast<const This*> (&expected);\n    return e != NULL && Base::equals(*e, tol) && fabs(this->delta_t_ - e->delta_t_) < tol;\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"4-way Gaussian Process Factor Pose3 VW\" << std::endl;\n    Base::print(\"\", keyFormatter);\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(delta_t_);\n  }\n\n}; // GaussianProcessPriorPose3\n\n\n} // namespace gpslam\n\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GaussianProcessPriorPose3VW> : public Testable<gpslam::GaussianProcessPriorPose3VW> {};\n}\n\n"
  },
  {
    "path": "gpslam/gp/GaussianProcessPriorRot3.h",
    "content": "/**\n *  @file  GaussianProcessPriorRot3.h\n *  @brief Rot3 GP prior\n *  @author Jing Dong\n **/\n\n#pragma once\n\n#include <gpslam/gp/GPutils.h>\n\n#include <gtsam/geometry/concepts.h>\n#include <gtsam/geometry/Rot3.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n#include <gtsam/base/Testable.h>\n\n#include <boost/lexical_cast.hpp>\n#include <boost/serialization/export.hpp>\n\n#include <ostream>\n\n\nnamespace gpslam {\n\n/**\n * 4-way factor for Gaussian Process prior factor, SO(3) version\n */\nclass GaussianProcessPriorRot3: public gtsam::NoiseModelFactor4<gtsam::Rot3,\n    gtsam::Vector3, gtsam::Rot3, gtsam::Vector3> {\n\nprivate:\n  double delta_t_;\n  typedef GaussianProcessPriorRot3 This;\n  typedef gtsam::NoiseModelFactor4<gtsam::Rot3, gtsam::Vector3, gtsam::Rot3, gtsam::Vector3> Base;\n\npublic:\n\n  GaussianProcessPriorRot3() {}\t/* Default constructor only for serialization */\n\n  /// Constructor\n  /// @param delta_t is the time between the two states\n  GaussianProcessPriorRot3(gtsam::Key poseKey1, gtsam::Key velKey1,\n      gtsam::Key poseKey2, gtsam::Key velKey2,\n      double delta_t, const gtsam::SharedNoiseModel& Qc_model) :\n    Base(gtsam::noiseModel::Gaussian::Covariance(calcQ<3>(getQc(Qc_model), delta_t)),\n        poseKey1, velKey1, poseKey2, velKey2) {\n    delta_t_ = delta_t;\n  }\n\n  virtual ~GaussianProcessPriorRot3() {}\n\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /// factor error function\n  gtsam::Vector evaluateError(const gtsam::Rot3& pose1, const gtsam::Vector3& vel1,\n      const gtsam::Rot3& pose2, const gtsam::Vector3& vel2,\n      boost::optional<gtsam::Matrix&> H1 = boost::none, boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none, boost::optional<gtsam::Matrix&> H4 = boost::none) const {\n\n    using namespace gtsam;\n\n    Matrix3 Hinv, Hcomp1, Hcomp2, Hlogmap;\n    Vector3 r;\n    if (H1 || H2 || H3 || H4)\n      r = Rot3::Logmap(pose1.inverse(Hinv).compose(pose2, Hcomp1, Hcomp2), Hlogmap);\n    else\n      r = Rot3::Logmap(pose1.inverse().compose(pose2));\n\n    // jacobians\n    if (H1) *H1 = (Matrix63() << Hlogmap * Hcomp1 * Hinv, Matrix3::Zero()).finished();\n    if (H2) *H2 = (Matrix63() << -delta_t_ * Matrix3::Identity(), -Matrix3::Identity()).finished();\n    if (H3) *H3 = (Matrix63() << Hlogmap * Hcomp2, Matrix3::Zero()).finished();\n    if (H4) *H4 = (Matrix63() << Matrix3::Zero(), Matrix3::Identity()).finished();\n\n    return (Vector(6) << (r - vel1 * delta_t_), (vel2 - vel1)).finished();\n  }\n\n  /** number of variables attached to this factor */\n  size_t size() const {\n    return 4;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e =  dynamic_cast<const This*> (&expected);\n    return e != NULL && Base::equals(*e, tol) && fabs(this->delta_t_ - e->delta_t_) < tol;\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"4-way Gaussian Process Factor Rot3\" << std::endl;\n    Base::print(\"\", keyFormatter);\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(delta_t_);\n  }\n\n}; // GaussianProcessPriorRot3\n\n\n} // namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GaussianProcessPriorRot3> : public Testable<gpslam::GaussianProcessPriorRot3> {};\n}\n\n"
  },
  {
    "path": "gpslam/gp/Pose3utils.cpp",
    "content": "/**\n*  @file  Pose3utils.cpp\n*  @author Jing Dong\n**/\n\n#include <gpslam/gp/Pose3utils.h>\n\n#include <cmath>\n\nusing namespace gtsam;\n\n\nnamespace gpslam {\n\n/* ************************************************************************** */\n// see Barfoot14tro eq. (25)\nVector6 getBodyCentricVb(const Pose3& pose1, const Pose3& pose2, double delta_t) {\n  return Pose3::Logmap(pose1.inverse().compose(pose2)) / delta_t;\n}\n\n/* ************************************************************************** */\nVector6 getBodyCentricVs(const Pose3& pose1, const Pose3& pose2, double delta_t) {\n  return Pose3::Logmap(pose2.compose(pose1.inverse())) / delta_t;\n}\n\n/* ************************************************************************** */\nvoid convertVbtoVW(const Vector6& v6, const Pose3& pose, Vector3& v, Vector3& w,\n    OptionalJacobian<3, 6> Hv, OptionalJacobian<3, 6> Hw) {\n\n  Matrix3 Hrv;\n  if (Hv) {\n    v = pose.rotation().rotate(v6.tail<3>(), boost::none, Hrv);\n    *Hv = (Matrix36() << Matrix3::Zero(), Hrv).finished();\n  } else {\n    v = pose.rotation().rotate(v6.tail<3>());\n  }\n\n  if (Hw)  {\n    w = pose.rotation().rotate(v6.head<3>(), boost::none, Hrv);\n    *Hw = (Matrix36() << Hrv, Matrix3::Zero()).finished();\n  } else {\n    w = pose.rotation().rotate(v6.head<3>());\n  }\n}\n\n/* ************************************************************************** */\nVector6 convertVWtoVb(const Vector3& v, const Vector3& w, const Pose3& pose,\n    OptionalJacobian<6, 3> Hv, OptionalJacobian<6, 3> Hw,\n    OptionalJacobian<6, 6> Hpose) {\n\n  Vector6 v6;\n  if (Hv || Hw || Hpose) {\n    Matrix3 Hrv, Hrw, Hpv, Hpw;\n    v6 = (Vector6() << pose.rotation().unrotate(w, Hpw, Hrw),\n        pose.rotation().unrotate(v, Hpv, Hrv)).finished();\n    if (Hv) *Hv = (Matrix63() << Matrix3::Zero(), Hrv).finished();\n    if (Hw) *Hw = (Matrix63() << Hrw, Matrix3::Zero()).finished();\n    if (Hpose) *Hpose = (Matrix6() << Hpw, Matrix3::Zero(), Hpv, Matrix3::Zero()).finished();\n  } else {\n    v6 = (Vector6() << pose.rotation().unrotate(w),\n        pose.rotation().unrotate(v)).finished();\n  }\n  return v6;\n}\n\n/* ************************************************************************** */\n// see Barfoot14tro eq. (102)\nMatrix3 leftJacobianPose3Q(const Vector6& xi) {\n  const Vector3 omega = xi.head(3), rho = xi.tail(3);\n  const double theta = omega.norm();        // rotation angle\n  const Matrix3 X = skewSymmetric(omega), Y = skewSymmetric(rho);\n\n  const Matrix3 XY = X*Y, YX = Y*X, XYX = X * YX;\n  if (fabs(theta) > 1e-5) {\n    const double sin_theta = sin(theta), cos_theta = cos(theta);\n    const double theta2 = theta * theta, theta3 = theta2 * theta,\n        theta4 = theta3 * theta, theta5 = theta4 * theta;\n\n    return 0.5*Y + (theta - sin_theta)/theta3 * (XY + YX + XYX)\n        - (1.0 - 0.5*theta2 - cos_theta)/theta4 * (X*XY + YX*X - 3.0*XYX)\n        - 0.5*((1.0 - 0.5*theta2 - cos_theta)/theta4 - 3.0*(theta - sin_theta - theta3/6.0)/theta5)\n          * (XYX*X + X*XYX);\n\n  } else {\n    return 0.5*Y + 1.0/6.0*(XY + YX + XYX)\n        - 1.0/24.0*(X*XY + YX*X - 3.0*XYX)\n        -0.5*(1.0/24.0 + 3.0/120.0) * (XYX*X + X*XYX);\n  }\n}\n\n/* ************************************************************************** */\nMatrix3 rightJacobianPose3Q(const Vector6& xi) {\n  const Vector3 omega = xi.head(3), rho = xi.tail(3);\n  const double theta = omega.norm();        // rotation angle\n  const Matrix3 X = skewSymmetric(omega), Y = skewSymmetric(rho);\n\n  const Matrix3 XY = X*Y, YX = Y*X, XYX = X * YX;\n  if (fabs(theta) > 1e-5) {\n    const double sin_theta = sin(theta), cos_theta = cos(theta);\n    const double theta2 = theta * theta, theta3 = theta2 * theta,\n        theta4 = theta3 * theta, theta5 = theta4 * theta;\n\n    return -0.5*Y + (theta - sin_theta)/theta3 * (XY + YX - XYX)\n        + (1.0 - 0.5*theta2 - cos_theta)/theta4 * (X*XY + YX*X - 3.0*XYX)\n        - 0.5*((1.0 - 0.5*theta2 - cos_theta)/theta4 - 3.0*(theta - sin_theta - theta3/6.0)/theta5)\n          * (XYX*X + X*XYX);\n\n  } else {\n    return -0.5*Y + 1.0/6.0*(XY + YX - XYX)\n        + 1.0/24.0*(X*XY + YX*X - 3.0*XYX)\n        -0.5*(1.0/24.0 + 3.0/120.0) * (XYX*X + X*XYX);\n  }\n}\n\n/* ************************************************************************** */\n// see Barfoot14tro eq. (100), note that in GTSAM rotation first in pose logmap\nMatrix6 leftJacobianPose3(const Vector6& xi) {\n  const Vector3 omega = xi.head(3);\n  const Matrix3 Q = leftJacobianPose3Q(xi);\n  const Matrix3 J = leftJacobianRot3(omega);\n\n  return (Matrix6() << J, Matrix::Zero(3,3), Q, J).finished();\n}\n\n/* ************************************************************************** */\n// see Barfoot14tro eq. (103)\nMatrix6 leftJacobianPose3inv(const Vector6& xi) {\n  const Vector3 omega = xi.head(3);\n  const Matrix3 Q = leftJacobianPose3Q(xi);\n  const Matrix3 Jinv = leftJacobianRot3inv(omega);\n\n  return (Matrix6() << Jinv, Matrix::Zero(3,3), -Jinv*Q*Jinv, Jinv).finished();\n}\n\n/* ************************************************************************** */\n// see Barfoot14tro eq. (98)\nMatrix3 leftJacobianRot3(const Vector3& omega) {\n  double theta2 = omega.dot(omega);\n  if (theta2 <= std::numeric_limits<double>::epsilon()) return Matrix::Identity(3,3);\n  const double theta = std::sqrt(theta2);     // rotation angle\n  const Vector3 dir = omega / theta;          // direction\n\n  const double sin_theta = sin(theta);\n  const Matrix3 A = skewSymmetric(omega) / theta;\n\n  return sin_theta / theta * Matrix::Identity(3,3) + (1 - sin_theta / theta) *\n      (dir * dir.transpose()) + (1 - cos(theta))/(theta) * A;\n}\n\n/* ************************************************************************** */\n// see Barfoot14tro eq. (99)\nMatrix3 leftJacobianRot3inv(const Vector3& omega) {\n  double theta2 = omega.dot(omega);\n  if (theta2 <= std::numeric_limits<double>::epsilon()) return Matrix::Identity(3,3);\n  const double theta = std::sqrt(theta2);     // rotation angle\n  const Vector3 dir = omega / theta;          // direction\n\n  const double theta_2 = theta/2.0;\n  const double cot_theta_2 = 1.0 / tan(theta_2);\n  const Matrix3 A = skewSymmetric(omega) / theta;\n\n  return theta_2*cot_theta_2 * Matrix::Identity(3,3) + (1 - theta_2*cot_theta_2) *\n      (dir * dir.transpose()) - theta_2 * A;\n}\n\n/* ************************************************************************** */\nMatrix6 jacobianMethodNumercialDiff(boost::function<Matrix6(const Vector6&)> func,\n    const Vector6& xi, const Vector6& x, double dxi) {\n  Matrix6 Diff = Matrix6();\n  for (size_t i = 0; i < 6; i++) {\n    Vector6 xi_dxip = xi, xi_dxin = xi;\n    xi_dxip(i) += dxi;\n    Matrix6 Jdiffp = func(xi_dxip);\n    xi_dxin(i) -= dxi;\n    Matrix6 Jdiffn = func(xi_dxin);\n    Diff.block<6,1>(0,i) = (Jdiffp - Jdiffn) / (2.0 * dxi) * x;\n  }\n  return Diff;\n}\n\n/* ************************************************************************** */\nMatrix6 rightJacobianPose3(const Vector6& xi) {\n  const Vector3 w = xi.head<3>();\n  const Matrix3 Jw = rightJacobianRot3(w);\n  const Matrix3 Q = rightJacobianPose3Q(xi);\n  Matrix6 J;\n  J << Jw, Matrix::Zero(3,3), Q, Jw;\n  return J;\n}\n\n/* ************************************************************************** */\nMatrix6 rightJacobianPose3inv(const Vector6& xi) {\n  const Vector3 w = xi.head<3>();\n  const Matrix3 Jw = rightJacobianRot3inv(w);\n  const Matrix3 Q = rightJacobianPose3Q(xi);\n  const Matrix3 Q2 = -Jw*Q*Jw;\n  Matrix6 J;\n  J << Jw, Matrix::Zero(3,3), Q2, Jw;\n  return J;\n}\n\n/* ************************************************************************** */\nMatrix3 rightJacobianRot3(const Vector3& omega) {\n  using std::cos;\n  using std::sin;\n  double theta2 = omega.dot(omega);\n  if (theta2 <= std::numeric_limits<double>::epsilon()) return Matrix::Identity(3,3);\n  double theta = std::sqrt(theta2);  // rotation angle\n  const Matrix3 Y = skewSymmetric(omega) / theta;\n  return Matrix::Identity(3,3) - ((1 - cos(theta)) / (theta)) * Y\n      + (1 - sin(theta) / theta) * Y * Y; // right Jacobian\n}\n\n/* ************************************************************************** */\nMatrix3 rightJacobianRot3inv(const Vector3& omega) {\n  using std::cos;\n  using std::sin;\n  double theta2 = omega.dot(omega);\n  if (theta2 <= std::numeric_limits<double>::epsilon()) return Matrix::Identity(3,3);\n  double theta = std::sqrt(theta2);  // rotation angle\n  const Matrix3 X = skewSymmetric(omega); // element of Lie algebra so(3): X = omega^\n  return Matrix::Identity(3,3) + 0.5 * X\n      + (1 / (theta * theta) - (1 + cos(theta)) / (2 * theta * sin(theta))) * X*X;\n}\n\n}\n\n"
  },
  {
    "path": "gpslam/gp/Pose3utils.h",
    "content": "/**\n *  @file  Pose3utils.h\n *  @brief Pose3 GP utils, mainly jacobians of expmap/logmap\n *  @author Xinyan Yan, Jing Dong\n **/\n\n#pragma once\n\n#include <gtsam/base/Vector.h>\n#include <gtsam/base/Matrix.h>\n#include <gtsam/geometry/Pose3.h>\n\n#include <boost/function.hpp>\n\n\nnamespace gpslam {\n\n// fixed size matrix for Dim-6 operation\ntypedef Eigen::Matrix<double, 12, 1> Vector_12;\ntypedef Eigen::Matrix<double, 12, 12> Matrix_12;\ntypedef Eigen::Matrix<double, 6, 12> Matrix_6_12;\ntypedef Eigen::Matrix<double, 12, 6> Matrix_12_6;\ntypedef Eigen::Matrix<double, 3, 12> Matrix_3_12;\ntypedef Eigen::Matrix<double, 12, 3> Matrix_12_3;\n\n\n/// get body-centric/body-frame velocity from two poses and delta_t\ngtsam::Vector6 getBodyCentricVs(const gtsam::Pose3& pose1, const gtsam::Pose3& pose2, double delta_t);\ngtsam::Vector6 getBodyCentricVb(const gtsam::Pose3& pose1, const gtsam::Pose3& pose2, double delta_t);\n\n/// convert 6d body-frame velocity into 3+3 world-frame line and angular velocity\n/// with optional jacobians\nvoid convertVbtoVW(const gtsam::Vector6& v6, const gtsam::Pose3& pose,\n    gtsam::Vector3& v, gtsam::Vector3& w,\n    gtsam::OptionalJacobian<3, 6> Hv = boost::none, gtsam::OptionalJacobian<3, 6> Hw = boost::none);\n\ngtsam::Vector6 convertVWtoVb(const gtsam::Vector3& v, const gtsam::Vector3& w,\n    const gtsam::Pose3& pose, gtsam::OptionalJacobian<6, 3> Hv = boost::none,\n    gtsam::OptionalJacobian<6, 3> Hw = boost::none,\n    gtsam::OptionalJacobian<6, 6> Hpose = boost::none);\n\n\n/// left Jacobian for Pose3 Expmap\ngtsam::Matrix6 leftJacobianPose3(const gtsam::Vector6& xi);\ngtsam::Matrix6 leftJacobianPose3inv(const gtsam::Vector6& xi);\ngtsam::Matrix3 leftJacobianPose3Q(const gtsam::Vector6& xi);\n\n/// right Jacobian for Pose3: jacobian of expmap/logmap\ngtsam::Matrix6 rightJacobianPose3(const gtsam::Vector6& xi);\ngtsam::Matrix6 rightJacobianPose3inv(const gtsam::Vector6& xi);\ngtsam::Matrix3 rightJacobianPose3Q(const gtsam::Vector6& xi);\n\n/// numerical diff of jacobian matrix methods\n/// output d(A(xi)*x)/dxi jacobian matrix\ngtsam::Matrix6 jacobianMethodNumercialDiff(boost::function<gtsam::Matrix6(\n    const gtsam::Vector6&)> func, const gtsam::Vector6& xi,\n    const gtsam::Vector6& x, double dxi = 1e-6);\n\n/// left Jacobian for Rot3 Expmap\ngtsam::Matrix3 leftJacobianRot3(const gtsam::Vector3& omega);\ngtsam::Matrix3 leftJacobianRot3inv(const gtsam::Vector3& omega);\n\n/// right Jacobian for Rot3: jacobian of expmap/logmap\ngtsam::Matrix3 rightJacobianRot3(const gtsam::Vector3& omega);\ngtsam::Matrix3 rightJacobianRot3inv(const gtsam::Vector3& omega);\n\n} // namespace gtsam\n\n\n"
  },
  {
    "path": "gpslam/gp/tests/testGaussianProcessInterpolatorLinear.cpp",
    "content": "/**\n*  @file testGaussianProcessInterpolatorLinear.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n\n#include <gpslam/gp/GaussianProcessInterpolatorLinear.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n// only test the 3 dim linear case (for Pose2 approximation)\ntypedef GaussianProcessInterpolatorLinear<3> GPBase3;\n\n/* ************************************************************************** */\nTEST(GaussianProcessInterpolatorLinear, equals) {\n  Matrix3 Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.03;\n  GPBase3 base1(Qc_model, dt, tau), base2(Qc_model, dt, tau);\n  EXPECT(assert_equal(base1, base2, 1e-9));\n\n  Matrix3 Qc2 = 0.02 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc2_model = noiseModel::Gaussian::Covariance(Qc2);\n  GPBase3 base3(Qc2_model, dt, tau);\n  EXPECT(!assert_equal(base1, base3, 1e-9));\n\n  dt = 0.2, tau = 0.03;\n  GPBase3 base4(Qc_model, dt, tau);\n  EXPECT(!assert_equal(base1, base4, 1e-9));\n\n  dt = 0.1, tau = 0.06;\n  GPBase3 base5(Qc_model, dt, tau);\n  EXPECT(!assert_equal(base1, base5, 1e-9));\n}\n\n/* ************************************************************************** */\nTEST(GaussianProcessInterpolatorLinear, interpolatePose) {\n  Vector3 p1, p2, expect, actual;\n  Vector3 v1, v2;\n  Matrix actualH1, actualH2, actualH3, actualH4;\n  Matrix expectH1, expectH2, expectH3, expectH4;\n  Matrix3 Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.03;\n  GPBase3 base(Qc_model, dt, tau);\n\n  // test at origin\n  p1 = (Vector3() << 0, 0, 0).finished();\n  p2 = (Vector3() << 0, 0, 0).finished();\n  v1 = (Vector3() << 0, 0, 0).finished();\n  v2 = (Vector3() << 0, 0, 0).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = (Vector3() << 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n  // test forward velocity\n  p1 = (Vector3() << 0, 0, 0).finished();\n  p2 = (Vector3() << 1, 0, 0).finished();\n  v1 = (Vector3() << 10, 0, 0).finished();\n  v2 = (Vector3() << 10, 0, 0).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = (Vector3() << 0.3, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n  // test rotate\n  p1 = (Vector3() << 0, 0, 0).finished();\n  p2 = (Vector3() << 0, 0, 0.3).finished();\n  v1 = (Vector3() << 0, 0, 3).finished();\n  v2 = (Vector3() << 0, 0, 3).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = (Vector3() << 0, 0, 0.09).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n  // some random stuff just for testing jacobian (error is not zero)\n  p1 = (Vector3() << 2, -5, 7).finished();\n  p2 = (Vector3() << -8, 4, -8).finished();\n  v1 = (Vector3() << -1, 2, -9).finished();\n  v2 = (Vector3() << 3, -4, 7).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expectH1 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector3(const Vector3&)>(\n      boost::bind(&GPBase3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testGaussianProcessInterpolatorPose2.cpp",
    "content": "/**\n*  @file testGaussianProcessInterpolatorPose2.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n\n#include <gpslam/gp/GaussianProcessInterpolatorPose2.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n/* ************************************************************************** */\nTEST(GaussianProcessInterpolatorPose2, interpolatePose) {\n  Pose2 p1, p2, expect, actual;\n  Vector3 v1, v2;\n  Matrix actualH1, actualH2, actualH3, actualH4;\n  Matrix expectH1, expectH2, expectH3, expectH4;\n  Matrix3 Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.03;\n  GaussianProcessInterpolatorPose2 base(Qc_model, dt, tau);\n\n  // test at origin\n  p1 = Pose2(0, 0, 0);\n  p2 = Pose2(0, 0, 0);\n  v1 = (Vector3() << 0, 0, 0).finished();\n  v2 = (Vector3() << 0, 0, 0).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Pose2(0, 0, 0);\n  expectH1 = numericalDerivative11(boost::function<Pose2(const Pose2&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Pose2(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Pose2(const Pose2&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Pose2(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n\n\n  // test forward\n  p1 = Pose2(0, 0, 0);\n  p2 = Pose2(0.1, 0, 0);\n  v1 = (Vector3() << 1, 0, 0).finished();\n  v2 = (Vector3() << 1, 0, 0).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Pose2(0.03, 0, 0);\n  expectH1 = numericalDerivative11(boost::function<Pose2(const Pose2&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Pose2(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Pose2(const Pose2&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Pose2(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // test rotate\n  p1 = Pose2(0, 0, 0);\n  p2 = Pose2(0, 0, 0.1);\n  v1 = (Vector3() << 0, 0, 1).finished();\n  v2 = (Vector3() << 0, 0, 1).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Pose2(0, 0, 0.03);\n  expectH1 = numericalDerivative11(boost::function<Pose2(const Pose2&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Pose2(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Pose2(const Pose2&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Pose2(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n\n\n  // some random stuff, just test jacobians\n  p1 = Pose2(3, -8, 2);\n  p2 = Pose2(-9, 3, 4);\n  v1 = (Vector3() << 0.5, 0.9, 0.7).finished();\n  v2 = (Vector3() << 0.6, -0.2, 0.8).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expectH1 = numericalDerivative11(boost::function<Pose2(const Pose2&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Pose2(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Pose2(const Pose2&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Pose2(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose2::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testGaussianProcessInterpolatorPose3.cpp",
    "content": "/**\n*  @file testGaussianProcessInterpolatorPose3.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n\n#include <gpslam/gp/GaussianProcessInterpolatorPose3.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n/* ************************************************************************** */\nTEST(GaussianProcessInterpolatorPose3, interpolatePose) {\n  Pose3 p1, p2, expect, actual;\n  Vector6 v1, v2;\n  Matrix actualH1, actualH2, actualH3, actualH4;\n  Matrix expectH1, expectH2, expectH3, expectH4;\n  Matrix6 Qc = 0.01 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.03;\n  GaussianProcessInterpolatorPose3 base(Qc_model, dt, tau);\n\n  // test at origin\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 0, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 0, 0, 0).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  expectH1 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Pose3(const Vector6&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Pose3(const Vector6&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n\n\n  // test forward\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.1, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.03, 0, 0));\n  expectH1 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Pose3(const Vector6&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Pose3(const Vector6&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // test rotate\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0.1, 0, 0), Point3(0, 0, 0));\n  v1 = (Vector6() << 0, 0, 1, 0, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 1, 0, 0, 0).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Pose3(Rot3::Ypr(0.03, 0, 0), Point3(0.0, 0, 0));\n  expectH1 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Pose3(const Vector6&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Pose3(const Vector6&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n\n\n  // some random stuff, just test jacobians\n  p1 = Pose3(Rot3::Ypr(0.4, -0.8, 0.2), Point3(3, -8, 2));\n  p2 = Pose3(Rot3::Ypr(0.1, 0.3, -0.5), Point3(-9, 3, 4));\n  v1 = (Vector6() << 0.1, -0.2, -1.4, 0.5, 0.9, 0.7).finished();\n  v2 = (Vector6() << 0.6, 0.3, -0.9, 0.4, -0.2, 0.8).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expectH1 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Pose3(const Vector6&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Pose3(const Vector6&)>(\n      boost::bind(&GaussianProcessInterpolatorPose3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testGaussianProcessInterpolatorPose3VW.cpp",
    "content": "/**\n*  @file testGaussianProcessInterpolatorPose3VW.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n\n#include <gpslam/gp/GaussianProcessInterpolatorPose3VW.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\nPose3 interWrapper(const GaussianProcessInterpolatorPose3VW& interpolater,\n    const Pose3& pose1, const Vector3& v1, const Vector3& omega1,\n    const Pose3& pose2, const Vector3& v2, const Vector3& omega2) {\n  return interpolater.interpolatePose(pose1, v1, omega1, pose2, v2, omega2);\n}\n\n/* ************************************************************************** */\nTEST(GaussianProcessInterpolatorPose3VW, interpolatePose) {\n  Pose3 p1, p2, expect, actual;\n  Vector3 v1, v2, w1, w2;\n  Matrix actualH1, actualH2, actualH3, actualH4, actualH5, actualH6;\n  Matrix expectH1, expectH2, expectH3, expectH4, expectH5, expectH6;\n  Matrix6 Qc = 0.01 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.03;\n  GaussianProcessInterpolatorPose3VW base(Qc_model, dt, tau);\n\n  // test at origin\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  v1 = Vector3(0, 0, 0); w1 = Vector3(0, 0, 0);\n  v2 = Vector3(0, 0, 0); w2 = Vector3(0, 0, 0);\n  actual = base.interpolatePose(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expect = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  expectH1 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(interWrapper, base, _1, v1, w1, p2, v2, w2)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, _1, w1, p2, v2, w2)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, _1, p2, v2, w2)), w1, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, _1, v2, w2)), p2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, p2, _1, w2)), v2, 1e-6);\n  expectH6 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, p2, v2, _1)), w2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-8));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-8));\n\n  // test forward\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.1, 0.2, 0));\n  v1 = Vector3(1, 2, 0); w1 = Vector3(0, 0, 0);\n  v2 = Vector3(1, 2, 0); w2 = Vector3(0, 0, 0);\n  actual = base.interpolatePose(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expect = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.03, 0.06, 0));\n  expectH1 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(interWrapper, base, _1, v1, w1, p2, v2, w2)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, _1, w1, p2, v2, w2)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, _1, p2, v2, w2)), w1, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, _1, v2, w2)), p2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, p2, _1, w2)), v2, 1e-4);\n  expectH6 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, p2, v2, _1)), w2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n\n  // test rotate\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0.1, 0, 0), Point3(0, 0, 0));\n  v1 = Vector3(0, 0, 0); w1 = Vector3(0, 0, 1);\n  v2 = Vector3(0, 0, 0); w2 = Vector3(0, 0, 1);\n  actual = base.interpolatePose(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expect = Pose3(Rot3::Ypr(0.03, 0, 0), Point3(0.0, 0, 0));\n  expectH1 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(interWrapper, base, _1, v1, w1, p2, v2, w2)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, _1, w1, p2, v2, w2)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, _1, p2, v2, w2)), w1, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, _1, v2, w2)), p2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, p2, _1, w2)), v2, 1e-6);\n  expectH6 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, p2, v2, _1)), w2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-8));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-8));\n\n\n  // some random stuff, just test jacobians\n  p1 = Pose3(Rot3::Ypr(0.4, -0.8, 0.2), Point3(3, -8, 2));\n  p2 = Pose3(Rot3::Ypr(0.1, 0.3, -0.5), Point3(-9, 3, 4));\n  v1 = Vector3(0.1, -0.2, -1.4); w1 = Vector3(0.5, 0.9, 0.7);\n  v1 = Vector3(0.6, 0.3, -0.9); w1 = Vector3(0.4, -0.2, 0.8);\n  actual = base.interpolatePose(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expectH1 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(interWrapper, base, _1, v1, w1, p2, v2, w2)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, _1, w1, p2, v2, w2)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, _1, p2, v2, w2)), w1, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Pose3(const Pose3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, _1, v2, w2)), p2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, p2, _1, w2)), v2, 1e-6);\n  expectH6 = numericalDerivative11(boost::function<Pose3(const Vector3&)>(\n      boost::bind(interWrapper, base, p1, v1, w1, p2, v2, _1)), w2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-8));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-8));\n\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testGaussianProcessInterpolatorRot3.cpp",
    "content": "/**\n*  @file testGaussianProcessInterpolatorRot3.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n\n#include <gpslam/gp/GaussianProcessInterpolatorRot3.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n/* ************************************************************************** */\nTEST(GaussianProcessInterpolatorRot3, interpolatePose) {\n  Rot3 p1, p2, expect, actual;\n  Vector3 v1, v2;\n  Matrix actualH1, actualH2, actualH3, actualH4;\n  Matrix expectH1, expectH2, expectH3, expectH4;\n  Matrix3 Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.03;\n  GaussianProcessInterpolatorRot3 base(Qc_model, dt, tau);\n\n  // test at origin\n  p1 = Rot3::Ypr(0, 0, 0);\n  p2 = Rot3::Ypr(0, 0, 0);\n  v1 = (Vector3() << 0, 0, 0).finished();\n  v2 = (Vector3() << 0, 0, 0).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Rot3::Ypr(0, 0, 0);\n  expectH1 = numericalDerivative11(boost::function<Rot3(const Rot3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Rot3(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Rot3(const Rot3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Rot3(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n\n\n  // test rotate x\n  p1 = Rot3::Ypr(0, 0, 0);\n  p2 = Rot3::Ypr(0, 0, 0.1);\n  v1 = (Vector3() << 1, 0, 0).finished();\n  v2 = (Vector3() << 1, 0, 0).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Rot3::Ypr(0, 0, 0.03);\n  expectH1 = numericalDerivative11(boost::function<Rot3(const Rot3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Rot3(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Rot3(const Rot3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Rot3(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // test rotate z\n  p1 = Rot3::Ypr(0, 0, 0);\n  p2 = Rot3::Ypr(0.1, 0, 0);\n  v1 = (Vector3() << 0, 0, 1).finished();\n  v2 = (Vector3() << 0, 0, 1).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Rot3::Ypr(0.03, 0, 0);\n  expectH1 = numericalDerivative11(boost::function<Rot3(const Rot3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Rot3(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Rot3(const Rot3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Rot3(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n\n\n  // some random stuff, just test jacobians\n  p1 = Rot3::Ypr(0.4, -0.8, 0.2);\n  p2 = Rot3::Ypr(0.1, 0.3, -0.5);\n  v1 = (Vector3() << 0.1, -0.2, -1.4).finished();\n  v2 = (Vector3() << 0.6, 0.3, -0.9).finished();\n  actual = base.interpolatePose(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expectH1 = numericalDerivative11(boost::function<Rot3(const Rot3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Rot3(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Rot3(const Rot3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Rot3(const Vector3&)>(\n      boost::bind(&GaussianProcessInterpolatorRot3::interpolatePose, base,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-8));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-8));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-8));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-8));\n\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testGaussianProcessPriorLinear.cpp",
    "content": "/**\n*  @file testGaussianProcessPriorLinear.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/gp/GaussianProcessPriorLinear.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n// only test the 3 dim linear case (for Pose2 approximation)\ntypedef GaussianProcessPriorLinear<3> GPPrior3;\n\n\n/* ************************************************************************** */\nTEST(GaussianProcessPriorLinear, Factor) {\n\n  const double delta_t = 0.1;\n  Matrix Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  Key key_pose1 = Symbol('x', 1), key_pose2 = Symbol('x', 2);\n  Key key_vel1 = Symbol('v', 1), key_vel2 = Symbol('v', 2);\n  GPPrior3 factor(key_pose1, key_vel1, key_pose2, key_vel2, delta_t, Qc_model);\n  Vector3 p1, p2;\n  Vector3 v1, v2;\n  Matrix actualH1, actualH2, actualH3, actualH4;\n  Matrix expectH1, expectH2, expectH3, expectH4;\n  Vector actual, expect;\n\n  // test at origin\n  p1 = (Vector3() << 0, 0, 0).finished();\n  p2 = (Vector3() << 0, 0, 0).finished();\n  v1 = (Vector3() << 0, 0, 0).finished();\n  v2 = (Vector3() << 0, 0, 0).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n  // test const forward v1 = v2 = 1.0\n  p1 = (Vector3() << 0, 0, 0).finished();\n  p2 = (Vector3() << 0.1, 0, 0).finished();\n  v1 = (Vector3() << 1, 0, 0).finished();\n  v2 = (Vector3() << 1, 0, 0).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n  // test const rotation w = 1.0\n  p1 = (Vector3() << 0, 0, 0).finished();\n  p2 = (Vector3() << 0, 0, 0.1).finished();\n  v1 = (Vector3() << 0, 0, 1).finished();\n  v2 = (Vector3() << 0, 0, 1).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n  // some random stuff just for testing jacobian (error is not zero)\n  p1 = (Vector3() << 2, -5, 7).finished();\n  p2 = (Vector3() << -8, 4, -8).finished();\n  v1 = (Vector3() << -1, 2, -9).finished();\n  v2 = (Vector3() << 3, -4, 7).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GPPrior3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n}\n\n/* ************************************************************************** */\nTEST(GaussianProcessPriorLinear, Optimization) {\n\n  /**\n   * A simple graph:\n   *\n   * p1   p2\n   * |    |\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   *\n   * p1 and p2 are pose prior factor to fix the poses, gp is the GP factor\n   * that get correct velocity of v1 and v2\n   */\n\n  noiseModel::Isotropic::shared_ptr model_prior =\n      noiseModel::Isotropic::Sigma(3, 0.001);\n  double delta_t = 0.1;\n  Matrix Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  Vector3 p1 = (Vector3() << 1, 0, 0).finished();\n  Vector3 p2 = (Vector3() << 1.1, 0, 0).finished();\n  Vector3 v1 = (Vector3() << 1, 0, 0).finished();\n  Vector3 v2 = (Vector3() << 1, 0, 0).finished();\n\n  // noisy init values\n  Vector3 p1init = (Vector3() << 1.1, 0.3, 0.5).finished();\n  Vector3 p2init = (Vector3() << 1.2, 0.4, -0.2).finished();\n  Vector3 v1init = (Vector3() << 1, 0.1, 0.2).finished();\n  Vector3 v2init = (Vector3() << 2.1, -1.2, 0.9).finished();\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Vector3>(Symbol('x', 1), p1, model_prior));\n  graph.add(PriorFactor<Vector3>(Symbol('x', 2), p2, model_prior));\n  //graph.add(PriorFactor<Vector3>(Symbol('v', 1), v1, model_prior));\n\n  graph.add(GPPrior3(Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, Qc_model));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), p1init);\n  init_values.insert(Symbol('v', 1), v1init);\n  init_values.insert(Symbol('x', 2), p2init);\n  init_values.insert(Symbol('v', 2), v2init);\n\n  GaussNewtonParams parameters;\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(p1, values.at<Vector3>(Symbol('x', 1)), 1e-6));\n  EXPECT(assert_equal(p2, values.at<Vector3>(Symbol('x', 2)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector3>(Symbol('v', 1)), 1e-6));\n  EXPECT(assert_equal(v2, values.at<Vector3>(Symbol('v', 2)), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testGaussianProcessPriorPose2.cpp",
    "content": "/**\n*  @file testGaussianProcessPriorPose2.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/gp/GaussianProcessPriorPose2.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n/* ************************************************************************** */\nTEST(GaussianProcessPriorPose2, Factor) {\n\n  const double delta_t = 0.1;\n  Matrix Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  Key key_pose1 = Symbol('x', 1), key_pose2 = Symbol('x', 2);\n  Key key_vel1 = Symbol('v', 1), key_vel2 = Symbol('v', 2);\n  GaussianProcessPriorPose2 factor(key_pose1, key_vel1, key_pose2, key_vel2, delta_t, Qc_model);\n  Pose2 p1, p2;\n  Vector3 v1, v2;\n  Matrix actualH1, actualH2, actualH3, actualH4;\n  Matrix expectH1, expectH2, expectH3, expectH4;\n  Vector actual, expect;\n\n\n  // test at origin\n  p1 = Pose2(0, 0, 0);\n  p2 = Pose2(0, 0, 0);\n  v1 = (Vector3() << 0, 0, 0).finished();\n  v2 = (Vector3() << 0, 0, 0).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // test at const forward velocity v1 = v2 = 1.0;\n  p1 = Pose2(0, 0, 0);\n  p2 = Pose2(0.1, 0, 0);\n  v1 = (Vector3() << 1, 0, 0).finished();\n  v2 = (Vector3() << 1, 0, 0).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // test at const rotation w1 = w2 = 1.0;\n  p1 = Pose2(0, 0, 0);\n  p2 = Pose2(0, 0, 0.1);\n  v1 = (Vector3() << 0, 0, 1).finished();\n  v2 = (Vector3() << 0, 0, 1).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // some random stuff just for testing jacobian (error is not zero)\n  p1 = Pose2(-0.1, 1.2, 0.3);\n  p2 = Pose2(2.4, -2.5, 3.7);\n  v1 = (Vector3() << 5, 4, 9).finished();\n  v2 = (Vector3() << 0, 6, 4).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorPose2::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n}\n\n/* ************************************************************************** */\nTEST(GaussianProcessPriorPose2, Optimization) {\n  /**\n   * A simple graph:\n   *\n   * p1   p2\n   * |    |\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   *\n   * p1 and p2 are pose prior factor to fix the poses, gp is the GP factor\n   * that get correct velocity of v2\n   */\n\n  noiseModel::Isotropic::shared_ptr model_prior = noiseModel::Isotropic::Sigma(3, 0.001);\n  double delta_t = 1;\n  Matrix Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  Pose2 pose1(0,0,0), pose2(1,0,0);\n  Vector3 v1 = (Vector3() << 1, 0, 0).finished();\n  Vector3 v2 = (Vector3() << 2.0, -0.5, 0.6).finished();   // rnd value\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Pose2>(Symbol('x', 1), pose1, model_prior));\n  graph.add(PriorFactor<Pose2>(Symbol('x', 2), pose2, model_prior));\n  //graph.add(PriorFactor<Vector6>(Symbol('v', 1), v1, model_prior));\n  graph.add(GaussianProcessPriorPose2(Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, Qc_model));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), pose1);\n  init_values.insert(Symbol('v', 1), v1);\n  init_values.insert(Symbol('x', 2), pose2);\n  init_values.insert(Symbol('v', 2), v2);\n\n  GaussNewtonParams parameters;\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(pose1, values.at<Pose2>(Symbol('x', 1)), 1e-6));\n  EXPECT(assert_equal(pose2, values.at<Pose2>(Symbol('x', 2)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector3>(Symbol('v', 1)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector3>(Symbol('v', 2)), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testGaussianProcessPriorPose3.cpp",
    "content": "/**\n*  @file testGaussianProcessPriorPose3.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/gp/GaussianProcessPriorPose3.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n/* ************************************************************************** */\nTEST(GaussianProcessPriorPose3Test, Factor) {\n\n  const double delta_t = 0.1;\n  Matrix Qc = 0.01 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  Key key_pose1 = Symbol('x', 1), key_pose2 = Symbol('x', 2);\n  Key key_vel1 = Symbol('v', 1), key_vel2 = Symbol('v', 2);\n  GaussianProcessPriorPose3 factor(key_pose1, key_vel1, key_pose2, key_vel2, delta_t, Qc_model);\n  Pose3 p1, p2;\n  Vector6 v1, v2;\n  Matrix actualH1, actualH2, actualH3, actualH4;\n  Matrix expectH1, expectH2, expectH3, expectH4;\n  Vector actual, expect;\n\n\n  // test at origin\n  p1 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  p2 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  v1 = (Vector6() << 0, 0, 0, 0, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 0, 0, 0).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(12) << 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // test at const forward velocity v1 = v2 = 1.0;\n  p1 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  p2 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.1, 0.0, 0.0));\n  v1 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(12) << 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // test at const rotation w1 = w2 = 1.0;\n  p1 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  p2 = Pose3(Rot3::Ypr(0.1, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  v1 = (Vector6() << 0, 0, 1, 0, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 1, 0, 0, 0).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(12) << 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // some random stuff just for testing jacobian (error is not zero)\n  p1 = Pose3(Rot3::Ypr(-0.1, 1.2, 0.3), Point3(-4.0, 2.0, 14.0));\n  p2 = Pose3(Rot3::Ypr(2.4, -2.5, 3.7), Point3(9.0, -8.0, -7.0));\n  v1 = (Vector6() << 2, 3, 1, 5, 4, 9).finished();\n  v2 = (Vector6() << 1, 3, 8, 0, 6, 4).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&GaussianProcessPriorPose3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-5));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-5));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n}\n\n/* ************************************************************************** */\nTEST(GaussianProcessPriorPose3Test, Optimization) {\n  /**\n   * A simple graph:\n   *\n   * p1   p2\n   * |    |\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   *\n   * p1 and p2 are pose prior factor to fix the poses, gp is the GP factor\n   * that get correct velocity of v2\n   */\n\n  noiseModel::Isotropic::shared_ptr model_prior =\n      noiseModel::Isotropic::Sigma(6, 0.001);\n  double delta_t = 1;\n  Matrix Qc = 0.01 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  Pose3 pose1(Rot3(), Point3(0,0,0)), pose2(Rot3(), Point3(1,0,0));\n  Vector6 v1 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  Vector6 v2 = (Vector6() << 0.1, 0.2, -0.3, 2.0, -0.5, 0.6).finished();   // rnd value\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Pose3>(Symbol('x', 1), pose1, model_prior));\n  graph.add(PriorFactor<Pose3>(Symbol('x', 2), pose2, model_prior));\n  //graph.add(PriorFactor<Vector6>(Symbol('v', 1), v1, model_prior));\n  graph.add(GaussianProcessPriorPose3(Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, Qc_model));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), pose1);\n  init_values.insert(Symbol('v', 1), v1);\n  init_values.insert(Symbol('x', 2), pose2);\n  init_values.insert(Symbol('v', 2), v2);\n\n  GaussNewtonParams parameters;\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(pose1, values.at<Pose3>(Symbol('x', 1)), 1e-6));\n  EXPECT(assert_equal(pose2, values.at<Pose3>(Symbol('x', 2)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector6>(Symbol('v', 1)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector6>(Symbol('v', 2)), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testGaussianProcessPriorPose3VW.cpp",
    "content": "/**\n*  @file testGaussianProcessPriorPose3VW.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/gp/GaussianProcessPriorPose3VW.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\nVector errorWrapper(const GaussianProcessPriorPose3VW& factor,\n    const Pose3& pose1, const Vector3& vel1, const Vector3& omega1,\n    const Pose3& pose2, const Vector3& vel2, const Vector3& omega2) {\n  return factor.evaluateError(pose1, vel1, omega1, pose2, vel2, omega2);\n}\n\n/* ************************************************************************** */\nTEST(GaussianProcessPriorPose3VW, Factor) {\n\n  const double delta_t = 0.1;\n  Matrix Qc = 0.01 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  Key key_pose1 = Symbol('x', 1), key_pose2 = Symbol('x', 2);\n  Key key_vel1 = Symbol('v', 1), key_vel2 = Symbol('v', 2);\n  Key key_omega1 = Symbol('w', 1), key_omega2 = Symbol('w', 2);\n  GaussianProcessPriorPose3VW factor(key_pose1, key_vel1, key_omega1, key_pose2, key_vel2, key_omega2, delta_t, Qc_model);\n  Pose3 p1, p2;\n  Vector3 v1, v2, w1, w2;\n  Matrix actualH1, actualH2, actualH3, actualH4, actualH5, actualH6;\n  Matrix expectH1, expectH2, expectH3, expectH4, expectH5, expectH6;\n  Vector actual, expect;\n\n\n  // test at origin\n  p1 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  p2 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  v1 = Vector3(0, 0, 0); w1 = Vector3(0, 0, 0);\n  v2 = Vector3(0, 0, 0); w2 = Vector3(0, 0, 0);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2, actualH3, actualH4, actualH5, actualH6);\n  expect = (Vector(12) << 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-6);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n\n  // test at const forward velocity v1 = v2 = 1.0;\n  p1 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  p2 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.1, 0.0, 0.0));\n  v1 = Vector3(1, 0, 0); w1 = Vector3(0, 0, 0);\n  v2 = Vector3(1, 0, 0); w2 = Vector3(0, 0, 0);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2, actualH3, actualH4, actualH5, actualH6);\n  expect = (Vector(12) << 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-6);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n\n  // test at const rotation w1 = w2 = 1.0;\n  p1 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  p2 = Pose3(Rot3::Ypr(0.1, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  v1 = Vector3(0, 0, 0); w1 = Vector3(0, 0, 1);\n  v2 = Vector3(0, 0, 0); w2 = Vector3(0, 0, 1);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2, actualH3, actualH4, actualH5, actualH6);\n  expect = (Vector(12) << 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-6);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n\n  // some random stuff just for testing jacobian (error is not zero)\n  p1 = Pose3(Rot3::Ypr(-0.1, 1.2, 0.3), Point3(-4.0, 2.0, 14.0));\n  p2 = Pose3(Rot3::Ypr(2.4, -2.5, 3.7), Point3(9.0, -8.0, -7.0));\n  v1 = Vector3(2, 3, 1); w1 = Vector3(5, 4, 9);\n  v2 = Vector3(1, 3, 8); w1 = Vector3(0, 6, 4);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2, actualH3, actualH4, actualH5, actualH6);\n  expect = (Vector(12) << 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-6);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n}\n\n/* ************************************************************************** */\nTEST(GaussianProcessPriorPose3VW, Optimization) {\n  /**\n   * A simple graph:\n   *\n   * p1   p2\n   * |    |\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   *\n   * p1 and p2 are pose prior factor to fix the poses, gp is the GP factor\n   * that get correct velocity of v2\n   */\n\n  noiseModel::Isotropic::shared_ptr model_prior =\n      noiseModel::Isotropic::Sigma(6, 0.001);\n  double delta_t = 1;\n  Matrix Qc = 0.01 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  Pose3 pose1(Rot3(), Point3(0,0,0)), pose2(Rot3(), Point3(1,0,0));\n  Vector3 v1 = Vector3(1, 0, 0), w1 = Vector3(0, 0, 0);\n  Vector3 v2 = Vector3(1, 0, 0), w2 = Vector3(0, 0, 0);\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Pose3>(Symbol('x', 1), pose1, model_prior));\n  graph.add(PriorFactor<Pose3>(Symbol('x', 2), pose2, model_prior));\n\n  graph.add(GaussianProcessPriorPose3VW(Symbol('x', 1), Symbol('v', 1), Symbol('w', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('w', 2), delta_t, Qc_model));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), pose1);\n  init_values.insert(Symbol('v', 1), v1);\n  init_values.insert(Symbol('w', 1), w1);\n  init_values.insert(Symbol('x', 2), pose2);\n  init_values.insert(Symbol('v', 2), v2);\n  init_values.insert(Symbol('w', 2), w2);\n\n  GaussNewtonParams parameters;\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(pose1, values.at<Pose3>(Symbol('x', 1)), 1e-6));\n  EXPECT(assert_equal(pose2, values.at<Pose3>(Symbol('x', 2)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector3>(Symbol('v', 1)), 1e-6));\n  EXPECT(assert_equal(v2, values.at<Vector3>(Symbol('v', 2)), 1e-6));\n  EXPECT(assert_equal(w1, values.at<Vector3>(Symbol('w', 1)), 1e-6));\n  EXPECT(assert_equal(w2, values.at<Vector3>(Symbol('w', 2)), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testGaussianProcessPriorRot3.cpp",
    "content": "/**\n*  @file testGaussianProcessPriorRot3.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/gp/GaussianProcessPriorRot3.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n/* ************************************************************************** */\nTEST(GaussianProcessPriorRot3, Factor) {\n\n  const double delta_t = 0.1;\n  Matrix Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  Key key_pose1 = Symbol('x', 1), key_pose2 = Symbol('x', 2);\n  Key key_vel1 = Symbol('v', 1), key_vel2 = Symbol('v', 2);\n  GaussianProcessPriorRot3 factor(key_pose1, key_vel1, key_pose2, key_vel2, delta_t, Qc_model);\n  Rot3 p1, p2;\n  Vector3 v1, v2;\n  Matrix actualH1, actualH2, actualH3, actualH4;\n  Matrix expectH1, expectH2, expectH3, expectH4;\n  Vector actual, expect;\n\n\n  // test at origin\n  p1 = Rot3::Ypr(0.0, 0.0, 0.0);\n  p2 = Rot3::Ypr(0.0, 0.0, 0.0);\n  v1 = (Vector3() << 0, 0, 0).finished();\n  v2 = (Vector3() << 0, 0, 0).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Rot3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Rot3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // test at const rotation of z, w1 = w2 = 1.0;\n  p1 = Rot3::Ypr(0.0, 0.0, 0.0);\n  p2 = Rot3::Ypr(0.1, 0.0, 0.0);\n  v1 = (Vector3() << 0, 0, 1).finished();\n  v2 = (Vector3() << 0, 0, 1).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Rot3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Rot3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n  // test at const rotation of x, w1 = w2 = 1.0;\n  p1 = Rot3::Ypr(0.0, 0.0, 0.0);\n  p2 = Rot3::Ypr(0.0, 0.0, 0.1);\n  v1 = (Vector3() << 1, 0, 0).finished();\n  v2 = (Vector3() << 1, 0, 0).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Rot3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Rot3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // some random stuff just for testing jacobian (error is not zero)\n  p1 = Rot3::Ypr(-0.1, 1.2, 0.3);\n  p2 = Rot3::Ypr(2.4, -2.5, 3.7);\n  v1 = (Vector3() << 2, 3, 1).finished();\n  v2 = (Vector3() << 1, 3, 8).finished();\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2, actualH3, actualH4);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Rot3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          _1, v1, p2, v2, boost::none, boost::none, boost::none, boost::none)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, _1, p2, v2, boost::none, boost::none, boost::none, boost::none)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Rot3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, v1, _1, v2, boost::none, boost::none, boost::none, boost::none)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&GaussianProcessPriorRot3::evaluateError, factor,\n          p1, v1, p2, _1, boost::none, boost::none, boost::none, boost::none)), v2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-5));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-5));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n}\n\n/* ************************************************************************** */\nTEST(GaussianProcessPriorRot3, Optimization) {\n  /**\n   * A simple graph:\n   *\n   * p1   p2\n   * |    |\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   *\n   * p1 and p2 are pose prior factor to fix the poses, gp is the GP factor\n   * that get correct velocity of v2\n   */\n\n  noiseModel::Isotropic::shared_ptr model_prior =\n      noiseModel::Isotropic::Sigma(3, 0.001);\n  double delta_t = 0.1;\n  Matrix Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  Rot3 pose1, pose2(Rot3::Ypr(0, 0, 0.1));\n  Vector3 v1 = (Vector3() << 1, 0, 0).finished();\n  Vector3 v2 = (Vector3() << 2.0, -0.5, 0.6).finished();   // rnd value\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Rot3>(Symbol('x', 1), pose1, model_prior));\n  graph.add(PriorFactor<Rot3>(Symbol('x', 2), pose2, model_prior));\n  //graph.add(PriorFactor<Vector6>(Symbol('v', 1), v1, model_prior));\n  graph.add(GaussianProcessPriorRot3(Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, Qc_model));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), pose1);\n  init_values.insert(Symbol('v', 1), v1);\n  init_values.insert(Symbol('x', 2), pose2);\n  init_values.insert(Symbol('v', 2), v2);\n\n  GaussNewtonParams parameters;\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(pose1, values.at<Rot3>(Symbol('x', 1)), 1e-6));\n  EXPECT(assert_equal(pose2, values.at<Rot3>(Symbol('x', 2)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector3>(Symbol('v', 1)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector3>(Symbol('v', 2)), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testPose3Utils.cpp",
    "content": "/**\n*  @file testPose3Utils.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/gp/Pose3utils.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n/* ************************************************************************** */\n// numerical method of jacobians\n// see Forster15rss eq. (A.48)\ntemplate <class LIE_TYPE>\nMatrix numericalLieLeftJacobian(const LIE_TYPE& lie, double dt) {\n  const size_t dim = LIE_TYPE::dimension;\n  Vector omega = LIE_TYPE::Logmap(lie);\n  Matrix J_expect = Matrix(dim, dim);\n  for (size_t i = 0; i < dim; i++) {\n    Vector dlogmap = Vector::Zero(dim);\n    dlogmap(i) = dt;\n    LIE_TYPE r = LIE_TYPE::Expmap(omega + dlogmap);\n    J_expect.block(0,i,dim,1) = LIE_TYPE::Logmap(r.compose(lie.inverse())) / dt;\n  }\n  return J_expect;\n}\n\ntemplate <class LIE_TYPE>\nMatrix numericalLieRightJacobian(const LIE_TYPE& lie, double dt) {\n  const size_t dim = LIE_TYPE::dimension;\n  Vector omega = LIE_TYPE::Logmap(lie);\n  Matrix J_expect = Matrix(dim, dim);\n  for (size_t i = 0; i < dim; i++) {\n    Vector dlogmap = Vector::Zero(dim);\n    dlogmap(i) = dt;\n    LIE_TYPE r = LIE_TYPE::Expmap(omega + dlogmap);\n    J_expect.block(0,i,dim,1) = LIE_TYPE::Logmap(lie.inverse().compose(r)) / dt;\n  }\n  return J_expect;\n}\n\n// TODO: why inverse version does not work??\n#if 0\n// see Barfoot14tro eq. (33), Forster15rss eq. (9)\ntemplate <class LIE_TYPE>\nMatrix numericalLieLeftJacobian(const LIE_TYPE& lie, double dt) {\n  const size_t dim = LIE_TYPE::dimension;\n  Vector omega = LIE_TYPE::Logmap(lie);\n  Matrix J_expect = Matrix(dim, dim);\n  for (size_t i = 0; i < dim; i++) {\n    Vector dlogmap = zero(dim);\n    dlogmap(i) = dt;\n    LIE_TYPE dr = LIE_TYPE::Expmap(dlogmap);\n    J_expect.block(0,i,dim,1) = (LIE_TYPE::Logmap(lie.compose(dr)) - omega) / dt;\n  }\n  return J_expect.inverse();\n}\n\ntemplate <class LIE_TYPE>\nMatrix numericalLieRightJacobian(const LIE_TYPE& lie, double dt) {\n  const size_t dim = LIE_TYPE::dimension;\n  Vector omega = LIE_TYPE::Logmap(lie);\n  Matrix J_expect = Matrix(dim, dim);\n  for (size_t i = 0; i < dim; i++) {\n    Vector dlogmap = zero(dim);\n    dlogmap(i) = dt;\n    LIE_TYPE dr = LIE_TYPE::Expmap(dlogmap);\n    J_expect.block(0,i,dim,1) = (LIE_TYPE::Logmap(dr.compose(lie)) - omega) / dt;\n  }\n  return J_expect.inverse();\n}\n#endif\n\n/* ************************************************************************** */\nTEST(testPose3Utils, getBodyCentricVelocity) {\n  Pose3 pose1, pose2;\n  Vector expect, actual;\n  double dt = 0.1;\n\n  // test at origin\n  pose1 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  pose2 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  actual = getBodyCentricVb(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  expect = (Vector(6) << 0, 0, 0, 0, 0, 0).finished();\n  actual = getBodyCentricVs(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n\n  // test forward x\n  pose1 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  pose2 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.1, 0.0, 0.0));\n  expect = (Vector(6) << 0, 0, 0, 1, 0, 0).finished();\n  actual = getBodyCentricVb(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  expect = (Vector(6) << 0, 0, 0, 1, 0, 0).finished();\n  actual = getBodyCentricVs(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n\n  // test rotate y\n  pose1 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  pose2 = Pose3(Rot3::Ypr(0.1, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  expect = (Vector(6) << 0, 0, 1, 0, 0, 0).finished();\n  actual = getBodyCentricVb(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  expect = (Vector(6) << 0, 0, 1, 0, 0, 0).finished();\n  actual = getBodyCentricVs(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n\n  // test forward x (body-y) at yaw=90 deg\n  pose1 = Pose3(Rot3::Ypr(M_PI / 2.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  pose2 = Pose3(Rot3::Ypr(M_PI / 2.0, 0.0, 0.0), Point3(0.1, 0.0, 0.0));\n  expect = (Vector(6) << 0, 0, 0, 0, -1, 0).finished();\n  actual = getBodyCentricVb(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  expect = (Vector(6) << 0, 0, 0, 1, 0, 0).finished();\n  actual = getBodyCentricVs(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n\n  // test rotate body+z at yaw=90 deg\n  pose1 = Pose3(Rot3::Ypr(M_PI / 2.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  pose2 = Pose3(Rot3::Ypr(M_PI / 2.0 + 0.1, 0.0, 0), Point3(0.0, 0.0, 0.0));\n  expect = (Vector(6) << 0, 0, 1, 0, 0, 0).finished();\n  actual = getBodyCentricVb(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  expect = (Vector(6) << 0, 0, 1, 0, 0, 0).finished();\n  actual = getBodyCentricVs(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n\n  // test rotate body+x at yaw=90 deg\n  pose1 = Pose3(Rot3::Ypr(M_PI / 2.0, 0.0, 0.0), Point3(1.0, 0.0, 0.0));\n  pose2 = Pose3(Rot3::Ypr(M_PI / 2.0, 0.0, 0.1), Point3(1.0, 0.0, 0.0));\n  expect = (Vector(6) << 1, 0, 0, 0, 0, 0).finished();\n  actual = getBodyCentricVb(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  expect = (Vector(6) << 0, 1, 0, 0, 0, 1).finished();\n  actual = getBodyCentricVs(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n\n  // circle motion\n  pose1 = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, -1.0, 0.0));\n  pose2 = Pose3(Rot3::Ypr(M_PI / 2.0, 0.0, 0.0), Point3(1.0, 0.0, 0.0));\n  expect = (Vector(6) << 0, 0, M_PI/2*10, M_PI/2*10, 0, 0).finished();\n  actual = getBodyCentricVb(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  expect = (Vector(6) << 0, 0, M_PI/2*10, 0, 0, 0).finished();\n  actual = getBodyCentricVs(pose1, pose2, dt);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n}\n\n/* ************************************************************************** */\nTEST(testPose3Utils, SO3Jacobian) {\n  Rot3 rotbase;\n  Matrix J_expect, J_actual;\n  const double dt = 1e-6;\n\n  // left jacobian\n  rotbase = Rot3::Ypr(0.0, 0.0, 0.0);\n  J_expect = numericalLieLeftJacobian(rotbase, dt);\n  J_actual = leftJacobianRot3(Rot3::Logmap(rotbase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  rotbase = Rot3::Ypr(1.0, 2.0, 3.0);\n  J_expect = numericalLieLeftJacobian(rotbase, dt);\n  J_actual = leftJacobianRot3(Rot3::Logmap(rotbase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  // inverse left jacobian\n  rotbase = Rot3::Ypr(0.0, 0.0, 0.0);\n  J_expect = numericalLieLeftJacobian(rotbase, dt).inverse();\n  J_actual = leftJacobianRot3inv(Rot3::Logmap(rotbase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  rotbase = Rot3::Ypr(1.0, 2.0, 3.0);\n  J_expect = numericalLieLeftJacobian(rotbase, dt).inverse();\n  J_actual = leftJacobianRot3inv(Rot3::Logmap(rotbase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  // right jacobian\n  rotbase = Rot3::Ypr(0.0, 0.0, 0.0);\n  J_expect = numericalLieRightJacobian(rotbase, dt);\n  J_actual = rightJacobianRot3(Rot3::Logmap(rotbase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  rotbase = Rot3::Ypr(1.0, 2.0, 3.0);\n  J_expect = numericalLieRightJacobian(rotbase, dt);\n  J_actual = rightJacobianRot3(Rot3::Logmap(rotbase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  // inverse right jacobian\n  rotbase = Rot3::Ypr(0.0, 0.0, 0.0);\n  J_expect = numericalLieRightJacobian(rotbase, dt).inverse();\n  J_actual = rightJacobianRot3inv(Rot3::Logmap(rotbase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  rotbase = Rot3::Ypr(1.0, 2.0, 3.0);\n  J_expect = numericalLieRightJacobian(rotbase, dt).inverse();\n  J_actual = rightJacobianRot3inv(Rot3::Logmap(rotbase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n}\n\n/* ************************************************************************** */\nTEST(testPose3Utils, SE3Jacobian) {\n  Pose3 posebase;\n  Matrix J_expect, J_actual;\n  const double dt = 1e-6;\n\n  // left jacobian\n  posebase = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  J_expect = numericalLieLeftJacobian(posebase, dt);\n  J_actual = leftJacobianPose3(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  posebase = Pose3(Rot3::Ypr(1e-5, 0.0, 1e-5), Point3(0.0, 2e-5, 0.0));\n  J_expect = numericalLieLeftJacobian(posebase, dt);\n  J_actual = leftJacobianPose3(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  posebase = Pose3(Rot3::Ypr(1.0, 2.0, 3.0), Point3(4.0, 5.0, 6.0));\n  J_expect = numericalLieLeftJacobian(posebase, dt);\n  J_actual = leftJacobianPose3(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  // left inverse jacobian\n  posebase = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  J_expect = numericalLieLeftJacobian(posebase, dt).inverse();\n  J_actual = leftJacobianPose3inv(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  posebase = Pose3(Rot3::Ypr(1e-5, 0.0, 1e-5), Point3(0.0, 2e-5, 0.0));\n  J_expect = numericalLieLeftJacobian(posebase, dt).inverse();\n  J_actual = leftJacobianPose3inv(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-8));\n\n  posebase = Pose3(Rot3::Ypr(1.0, 2.0, 3.0), Point3(4.0, 5.0, 6.0));\n  J_expect = numericalLieLeftJacobian(posebase, dt).inverse();\n  J_actual = leftJacobianPose3inv(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-5));\n\n  // right jacobian\n  posebase = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  J_expect = numericalLieRightJacobian(posebase, dt);\n  J_actual = rightJacobianPose3(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  posebase = Pose3(Rot3::Ypr(1e-5, 0.0, 1e-5), Point3(0.0, 2e-5, 0.0));\n  J_expect = numericalLieRightJacobian(posebase, dt);\n  J_actual = rightJacobianPose3(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  posebase = Pose3(Rot3::Ypr(1.0, 2.0, 3.0), Point3(4.0, 5.0, 6.0));\n  J_expect = numericalLieRightJacobian(posebase, dt);\n  J_actual = rightJacobianPose3(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  // inverse right jacobian\n  posebase = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  J_expect = numericalLieRightJacobian(posebase, dt).inverse();\n  J_actual = rightJacobianPose3inv(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-6));\n\n  posebase = Pose3(Rot3::Ypr(1e-5, 0.0, 1e-5), Point3(0.0, 2e-5, 0.0));\n  J_expect = numericalLieRightJacobian(posebase, dt).inverse();\n  J_actual = rightJacobianPose3inv(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-8));\n\n  posebase = Pose3(Rot3::Ypr(1.0, 2.0, 3.0), Point3(4.0, 5.0, 6.0));\n  J_expect = numericalLieRightJacobian(posebase, dt).inverse();\n  J_actual = rightJacobianPose3inv(Pose3::Logmap(posebase));\n  EXPECT(assert_equal(J_expect, J_actual, 1e-5));\n}\n\n/* ************************************************************************** */\nTEST(testPose3Utils, SE3velocity) {\n  // check Anderson15iros eq. (8)\n  Pose3 posebase, poseadd;\n  Vector v_expect, v_actual;\n  Vector dlogmap;\n  const double dt = 0.01;\n\n  // origin, zero vel\n  posebase = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0, 0, 0));\n  dlogmap = (Vector(6) << 0, 0, 0, 0, 0, 0).finished() * 1e-4;\n  poseadd = Pose3::Expmap(Pose3::Logmap(posebase) + dlogmap);\n  v_expect = getBodyCentricVb(posebase, poseadd, dt);\n  v_actual = rightJacobianPose3(Pose3::Logmap(posebase)) * dlogmap / dt;\n  EXPECT(assert_equal(v_expect, v_actual, 1e-6));\n  v_expect = getBodyCentricVs(posebase, poseadd, dt);\n  v_actual = leftJacobianPose3(Pose3::Logmap(posebase)) * dlogmap / dt;\n  EXPECT(assert_equal(v_expect, v_actual, 1e-6));\n\n  // origin, non zero vel\n  posebase = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0, 0, 0));\n  dlogmap = (Vector(6) << 1, 2, -4, 5, 2, 3).finished() * 1e-4;\n  poseadd = Pose3::Expmap(Pose3::Logmap(posebase) + dlogmap);\n  v_expect = getBodyCentricVb(posebase, poseadd, dt);\n  v_actual = rightJacobianPose3(Pose3::Logmap(posebase)) * dlogmap / dt;\n  EXPECT(assert_equal(v_expect, v_actual, 1e-6));\n  v_expect = getBodyCentricVs(posebase, poseadd, dt);\n  v_actual = leftJacobianPose3(Pose3::Logmap(posebase)) * dlogmap / dt;\n  EXPECT(assert_equal(v_expect, v_actual, 1e-6));\n\n  // rnd pose, non zero vel\n  posebase = Pose3(Rot3::Ypr(2.4, 1.2, 3.9), Point3(43, -5, 12));\n  dlogmap = (Vector(6) << 1, 2, -4, 5, 2, 3).finished() * 1e-4;\n  poseadd = Pose3::Expmap(Pose3::Logmap(posebase) + dlogmap);\n  v_expect = getBodyCentricVb(posebase, poseadd, dt);\n  v_actual = rightJacobianPose3(Pose3::Logmap(posebase)) * dlogmap / dt;\n  EXPECT(assert_equal(v_expect, v_actual, 1e-4));\n  v_expect = getBodyCentricVs(posebase, poseadd, dt);\n  v_actual = leftJacobianPose3(Pose3::Logmap(posebase)) * dlogmap / dt;\n  EXPECT(assert_equal(v_expect, v_actual, 1e-4));\n}\n\n/* ************************************************************************** */\n// wrap v from convertVbtoVW\nVector3 vWrapperVb(const Vector6& v6, const Pose3& pose) {\n  Vector3 v,w;\n  convertVbtoVW(v6, pose, v, w);\n  return v;\n}\n\n// wrap w from convertVbtoVW\nVector3 wWrapperVb(const Vector6& v6, const Pose3& pose) {\n  Vector3 v,w;\n  convertVbtoVW(v6, pose, v, w);\n  return w;\n}\n\nTEST(testPose3Utils, convertVelocityVW) {\n  Pose3 pose;\n  Vector6 v6exp, v6act;\n  Vector3 vact, wact, vexp, wexp;\n  Matrix36 H1vexp, H1vact, H1wexp, H1wact;\n  Matrix63 H2vexp, H2vact, H2wexp, H2wact;\n  Matrix6 H2pexp, H2pact;\n\n\n  // zero pose\n  pose = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  v6exp = (Vector6() << 1, 0, 0, 1, 0, 0).finished();\n  vexp = Vector3(1, 0, 0), wexp = Vector3(1, 0, 0);\n  convertVbtoVW(v6exp, pose, vact, wact, H1vact, H1wact);\n  H1vexp = numericalDerivative11(boost::function<Vector3(const Vector6&)>(\n      boost::bind(&vWrapperVb, _1, pose)), v6exp, 1e-6);\n  H1wexp = numericalDerivative11(boost::function<Vector3(const Vector6&)>(\n      boost::bind(&wWrapperVb, _1, pose)), v6exp, 1e-6);\n  EXPECT(assert_equal(vexp, vact, 1e-9));\n  EXPECT(assert_equal(wexp, wact, 1e-9));\n  EXPECT(assert_equal(H1vexp, H1vact, 1e-6));\n  EXPECT(assert_equal(H1wexp, H1wact, 1e-6));\n  v6act = convertVWtoVb(vexp, wexp, pose, H2vact, H2wact, H2pact);\n  H2vexp = numericalDerivative11(boost::function<Vector6(const Vector3&)>(\n      boost::bind(&convertVWtoVb, _1, wexp, pose, boost::none, boost::none, boost::none)), vexp, 1e-6);\n  H2wexp = numericalDerivative11(boost::function<Vector6(const Vector3&)>(\n      boost::bind(&convertVWtoVb, vexp, _1, pose, boost::none, boost::none, boost::none)), wexp, 1e-6);\n  H2pexp = numericalDerivative11(boost::function<Vector6(const Pose3&)>(\n      boost::bind(&convertVWtoVb, vexp, wexp, _1, boost::none, boost::none, boost::none)), pose, 1e-6);\n  EXPECT(assert_equal(v6exp, v6act, 1e-9));\n  EXPECT(assert_equal(H2vexp, H2vact, 1e-6));\n  EXPECT(assert_equal(H2wexp, H2wact, 1e-6));\n  EXPECT(assert_equal(H2pexp, H2pact, 1e-6));\n\n\n  pose = Pose3(Rot3::Ypr(0.0, 0.0, 0.0), Point3(3.0, 4.0, 5.0));\n  v6exp = (Vector6() << 1, -2, -3, 1, 2, 3).finished();\n  vexp = Vector3(1, 2, 3), wexp = Vector3(1, -2, -3);\n  convertVbtoVW(v6exp, pose, vact, wact, H1vact, H1wact);\n  H1vexp = numericalDerivative11(boost::function<Vector3(const Vector6&)>(\n      boost::bind(&vWrapperVb, _1, pose)), v6exp, 1e-6);\n  H1wexp = numericalDerivative11(boost::function<Vector3(const Vector6&)>(\n      boost::bind(&wWrapperVb, _1, pose)), v6exp, 1e-6);\n  EXPECT(assert_equal(vexp, vact, 1e-9));\n  EXPECT(assert_equal(wexp, wact, 1e-9));\n  EXPECT(assert_equal(H1vexp, H1vact, 1e-6));\n  EXPECT(assert_equal(H1wexp, H1wact, 1e-6));\n  v6act = convertVWtoVb(vexp, wexp, pose, H2vact, H2wact, H2pact);\n  H2vexp = numericalDerivative11(boost::function<Vector6(const Vector3&)>(\n      boost::bind(&convertVWtoVb, _1, wexp, pose, boost::none, boost::none, boost::none)), vexp, 1e-6);\n  H2wexp = numericalDerivative11(boost::function<Vector6(const Vector3&)>(\n      boost::bind(&convertVWtoVb, vexp, _1, pose, boost::none, boost::none, boost::none)), wexp, 1e-6);\n  H2pexp = numericalDerivative11(boost::function<Vector6(const Pose3&)>(\n      boost::bind(&convertVWtoVb, vexp, wexp, _1, boost::none, boost::none, boost::none)), pose, 1e-6);\n  EXPECT(assert_equal(v6exp, v6act, 1e-9));\n  EXPECT(assert_equal(H2vexp, H2vact, 1e-6));\n  EXPECT(assert_equal(H2wexp, H2wact, 1e-6));\n  EXPECT(assert_equal(H2pexp, H2pact, 1e-6));\n\n\n  // yaw = 90 deg pose\n  pose = Pose3(Rot3::Ypr(M_PI/2.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  v6exp = (Vector6() << 0, 0, 1, 0, -1, 0).finished();\n  vexp = Vector3(1, 0, 0), wexp = Vector3(0, 0, 1);\n  convertVbtoVW(v6exp, pose, vact, wact, H1vact, H1wact);\n  H1vexp = numericalDerivative11(boost::function<Vector3(const Vector6&)>(\n      boost::bind(&vWrapperVb, _1, pose)), v6exp, 1e-6);\n  H1wexp = numericalDerivative11(boost::function<Vector3(const Vector6&)>(\n      boost::bind(&wWrapperVb, _1, pose)), v6exp, 1e-6);\n  EXPECT(assert_equal(vexp, vact, 1e-9));\n  EXPECT(assert_equal(wexp, wact, 1e-9));\n  EXPECT(assert_equal(H1vexp, H1vact, 1e-6));\n  EXPECT(assert_equal(H1wexp, H1wact, 1e-6));\n  v6act = convertVWtoVb(vexp, wexp, pose, H2vact, H2wact, H2pact);\n  H2vexp = numericalDerivative11(boost::function<Vector6(const Vector3&)>(\n      boost::bind(&convertVWtoVb, _1, wexp, pose, boost::none, boost::none, boost::none)), vexp, 1e-6);\n  H2wexp = numericalDerivative11(boost::function<Vector6(const Vector3&)>(\n      boost::bind(&convertVWtoVb, vexp, _1, pose, boost::none, boost::none, boost::none)), wexp, 1e-6);\n  H2pexp = numericalDerivative11(boost::function<Vector6(const Pose3&)>(\n      boost::bind(&convertVWtoVb, vexp, wexp, _1, boost::none, boost::none, boost::none)), pose, 1e-6);\n  EXPECT(assert_equal(v6exp, v6act, 1e-9));\n  EXPECT(assert_equal(H2vexp, H2vact, 1e-6));\n  EXPECT(assert_equal(H2wexp, H2wact, 1e-6));\n  EXPECT(assert_equal(H2pexp, H2pact, 1e-6));\n\n\n  pose = Pose3(Rot3::Ypr(M_PI/2.0, 0.0, 0.0), Point3(0.0, 0.0, 0.0));\n  v6exp = (Vector6() << 0, 0, 1, 4, 3, 0).finished();\n  vexp = Vector3(-3, 4, 0), wexp = Vector3(0, 0, 1);\n  convertVbtoVW(v6exp, pose, vact, wact, H1vact, H1wact);\n  H1vexp = numericalDerivative11(boost::function<Vector3(const Vector6&)>(\n      boost::bind(&vWrapperVb, _1, pose)), v6exp, 1e-6);\n  H1wexp = numericalDerivative11(boost::function<Vector3(const Vector6&)>(\n      boost::bind(&wWrapperVb, _1, pose)), v6exp, 1e-6);\n  EXPECT(assert_equal(vexp, vact, 1e-9));\n  EXPECT(assert_equal(wexp, wact, 1e-9));\n  EXPECT(assert_equal(H1vexp, H1vact, 1e-6));\n  EXPECT(assert_equal(H1wexp, H1wact, 1e-6));\n  v6act = convertVWtoVb(vexp, wexp, pose, H2vact, H2wact, H2pact);\n  H2vexp = numericalDerivative11(boost::function<Vector6(const Vector3&)>(\n      boost::bind(&convertVWtoVb, _1, wexp, pose, boost::none, boost::none, boost::none)), vexp, 1e-6);\n  H2wexp = numericalDerivative11(boost::function<Vector6(const Vector3&)>(\n      boost::bind(&convertVWtoVb, vexp, _1, pose, boost::none, boost::none, boost::none)), wexp, 1e-6);\n  H2pexp = numericalDerivative11(boost::function<Vector6(const Pose3&)>(\n      boost::bind(&convertVWtoVb, vexp, wexp, _1, boost::none, boost::none, boost::none)), pose, 1e-6);\n  EXPECT(assert_equal(v6exp, v6act, 1e-9));\n  EXPECT(assert_equal(H2vexp, H2vact, 1e-6));\n  EXPECT(assert_equal(H2wexp, H2wact, 1e-6));\n  EXPECT(assert_equal(H2pexp, H2pact, 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/gp/tests/testSerializationGP.cpp",
    "content": "/**\n*  @file testSerialization.cpp\n*  @brief test serialization of all factors\n*  @author Jing Dong\n**/\n\n#include <gpslam/gp/GaussianProcessInterpolatorLinear.h>\n/*\n#include <gpslam/gp/GaussianProcessFactorBasePose3.h>\n#include <gpslam/gp/GaussianProcessFactorBasePose3VW.h>\n#include <gpslam/gp/GaussianProcessFactorBasePose2.h>\n#include <gpslam/gp/GaussianProcessFactorBaseRot3.h>\n\n#include <gpslam/gp/GaussianProcessPriorLinear.h>\n#include <gpslam/gp/GaussianProcessPriorPose3.h>\n#include <gpslam/gp/GaussianProcessPriorPose3VW.h>\n#include <gpslam/gp/GaussianProcessPriorPose2.h>\n#include <gpslam/gp/GaussianProcessPriorRot3.h>\n*/\n#include <gtsam/base/serializationTestHelpers.h>\n\n#include <CppUnitLite/TestHarness.h>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\nusing namespace gtsam::serializationTestHelpers;\n\n\nBOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, \"gtsam_noiseModel_Constrained\");\nBOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, \"gtsam_noiseModel_Diagonal\");\nBOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, \"gtsam_noiseModel_Gaussian\");\nBOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, \"gtsam_noiseModel_Unit\");\nBOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, \"gtsam_noiseModel_Isotropic\");\nBOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, \"gtsam_SharedNoiseModel\");\nBOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, \"gtsam_SharedDiagonal\");\n\n/* ************************************************************************** */\n// data\nstatic SharedNoiseModel Qcmodel_6 = noiseModel::Isotropic::Sigma(6, 0.1);\nstatic SharedNoiseModel Qcmodel_3 = noiseModel::Isotropic::Sigma(3, 0.1);\n\n// bases\nstatic GaussianProcessInterpolatorLinear<6> gp_base_linear(Qcmodel_6, 0.1, 0.04);\n/*\nstatic GaussianProcessFactorBasePose3 gp_base_pose3(Qcmodel_6, 0.1, 0.04);\nstatic GaussianProcessFactorBasePose3VW gp_base_pose3vw(Qcmodel_6, 0.1, 0.04);\nstatic GaussianProcessFactorBasePose2 gp_base_pose2(Qcmodel_3, 0.1, 0.04);\nstatic GaussianProcessFactorBaseRot3 gp_base_rot3(Qcmodel_3, 0.1, 0.04);\n\n// factors\nstatic GaussianProcessPriorLinear<6> gp_prior_linear(1, 2, 3, 4, 0.1, Qcmodel_6);\nstatic GaussianProcessPriorPose3 gp_prior_pose3(1, 2, 3, 4, 0.1, Qcmodel_6);\nstatic GaussianProcessPriorPose3VW gp_prior_pose3_vw(1, 2, 3, 4, 5, 6, 0.1, Qcmodel_6);\nstatic GaussianProcessPriorPose2 gp_prior_pose2(1, 2, 3, 4, 0.1, Qcmodel_3);\nstatic GaussianProcessPriorRot3 gp_prior_rot3(1, 2, 3, 4, 0.1, Qcmodel_3);\n*/\n\n/* ************************************************************************** */\nTEST_UNSAFE(SerializationGP, text) {\n  EXPECT(equalsObj(gp_base_linear));\n  /*\n  EXPECT(equalsObj(gp_base_pose3));\n  EXPECT(equalsObj(gp_base_pose3vw));\n  EXPECT(equalsObj(gp_base_pose2));\n  EXPECT(equalsObj(gp_base_rot3));\n\n  EXPECT(equalsObj(gp_prior_linear));\n  EXPECT(equalsObj(gp_prior_pose3));\n  EXPECT(equalsObj(gp_prior_pose3_vw));\n  EXPECT(equalsObj(gp_prior_pose2));\n  EXPECT(equalsObj(gp_prior_rot3));\n  */\n}\n\n/* ************************************************************************** */\nTEST_UNSAFE(SerializationGP, xml) {\n  EXPECT(equalsXML(gp_base_linear));\n  /*\n  EXPECT(equalsXML(gp_base_pose3));\n  EXPECT(equalsXML(gp_base_pose3vw));\n  EXPECT(equalsXML(gp_base_pose2));\n  EXPECT(equalsXML(gp_base_rot3));\n\n  EXPECT(equalsXML(gp_prior_linear));\n  EXPECT(equalsXML(gp_prior_pose3));\n  EXPECT(equalsXML(gp_prior_pose3_vw));\n  EXPECT(equalsXML(gp_prior_pose2));\n  EXPECT(equalsXML(gp_prior_rot3));\n  */\n}\n\n/* ************************************************************************** */\nTEST_UNSAFE(SerializationGP, binary) {\n  EXPECT(equalsBinary(gp_base_linear));\n  /*\n  EXPECT(equalsBinary(gp_base_pose3));\n  EXPECT(equalsBinary(gp_base_pose3vw));\n  EXPECT(equalsBinary(gp_base_pose2));\n  EXPECT(equalsBinary(gp_base_rot3));\n\n  EXPECT(equalsBinary(gp_prior_linear));\n  EXPECT(equalsBinary(gp_prior_pose3));\n  EXPECT(equalsBinary(gp_prior_pose3_vw));\n  EXPECT(equalsBinary(gp_prior_pose2));\n  EXPECT(equalsBinary(gp_prior_rot3));\n  */\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/slam/CMakeLists.txt",
    "content": "# Install headers\nfile(GLOB slam_headers \"*.h\")\ninstall(FILES ${slam_headers} DESTINATION include/gpslam/slam)\n\n# Build tests\ngtsamAddTestsGlob(slam \"tests/*.cpp\" \"\" ${PROJECT_NAME})\n"
  },
  {
    "path": "gpslam/slam/GPInterpolatedAttitudeFactorRot3.h",
    "content": "/**\n *  @file  GPInterpolatedAttitudeFactorRot3.h\n *  @author Frank Dellaert, Jing Dong\n *  @brief Use Acceleration to get Attitude, GP interpolated version\n **/\n\n#pragma once\n\n#include <gpslam/gp/GaussianProcessInterpolatorRot3.h>\n\n#include <gtsam/navigation/AttitudeFactor.h>\n\n\nnamespace gpslam {\n\n/**\n * Binary factor for an attitude measurement, GP interpolated\n */\nclass GPInterpolatedAttitudeFactorRot3: public gtsam::NoiseModelFactor4<\n    gtsam::Rot3, gtsam::Vector3, gtsam::Rot3, gtsam::Vector3>, public gtsam::AttitudeFactor {\n\nprivate:\n  // interpolater\n  GaussianProcessInterpolatorRot3 GPbase_;\n\n  typedef GPInterpolatedAttitudeFactorRot3 This;\n  typedef gtsam::NoiseModelFactor4<gtsam::Rot3, gtsam::Vector3, gtsam::Rot3, gtsam::Vector3> Base;\n  typedef GaussianProcessInterpolatorRot3 GPBase;\n\n\npublic:\n\n  /// shorthand for a smart pointer to a factor\n  typedef boost::shared_ptr<This> shared_ptr;\n\n  GPInterpolatedAttitudeFactorRot3() {} /* Default constructor */\n\n  /**\n   * Constructor\n   * @param nZ measured direction in navigation frame\n   * @param meas_model Gaussian noise model\n   * @param bRef reference direction in body frame (default Z-axis)\n   */\n  GPInterpolatedAttitudeFactorRot3(\n      gtsam::Key poseKey1, gtsam::Key velKey1, gtsam::Key poseKey2, gtsam::Key velKey2,\n      double delta_t, double tau, const gtsam::SharedNoiseModel& Qc_model,\n      const gtsam::SharedNoiseModel& meas_model, const gtsam::Unit3& nZ,\n      const gtsam::Unit3& bRef = gtsam::Unit3(0, 0, 1)) :\n        Base(meas_model, poseKey1, velKey1, poseKey2, velKey2),\n        gtsam::AttitudeFactor(nZ, bRef), GPbase_(Qc_model, delta_t, tau) {\n  }\n\n  virtual ~GPInterpolatedAttitudeFactorRot3() {}\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /** factor error */\n  gtsam::Vector evaluateError(const gtsam::Rot3& pose1, const gtsam::Vector3& vel1,\n      const gtsam::Rot3& pose2, const gtsam::Vector3& vel2,\n      boost::optional<gtsam::Matrix&> H1 = boost::none, boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none, boost::optional<gtsam::Matrix&> H4 = boost::none) const {\n\n    using namespace gtsam;\n\n    // interpolate pose\n    if (H1 || H2 || H3 || H4) {\n      Matrix Hint1, Hint2, Hint3, Hint4;\n      Rot3 pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2, Hint1, Hint2, Hint3, Hint4);\n\n      Matrix Hrot;\n      Vector err = attitudeError(pose, Hrot);\n      GPBase::updatePoseJacobians(Hrot, Hint1, Hint2, Hint3, Hint4, H1, H2, H3, H4);\n\n      return err;\n\n    } else {\n      Rot3 pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2);\n      return attitudeError(pose);\n    }\n  }\n\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e = dynamic_cast<const This*> (&expected);\n    return e != NULL && Base::equals(*e, tol)\n        && this->GPbase_.equals(e->GPbase_);\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"GP Interpolated AttitudeFactor\" << std::endl;\n    Base::print(\"\", keyFormatter);\n    GPbase_.print(\"Measurement interpolated at: \");\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & boost::serialization::make_nvp(\"NoiseModelFactor4\",\n        boost::serialization::base_object<Base>(*this));\n    ar & BOOST_SERIALIZATION_NVP(GPbase_);\n  }\n\n}; // GPInterpolatedAttitudeFactorRot3\n\n} // namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GPInterpolatedAttitudeFactorRot3> : public Testable<gpslam::GPInterpolatedAttitudeFactorRot3> {};\n}\n\n"
  },
  {
    "path": "gpslam/slam/GPInterpolatedGPSFactorPose3.h",
    "content": "/**\n *  @file  GPInterpolatedGPSFactorPose3.h\n *  @author Jing Dong\n *  @brief Translational measurement like GPS, GP interpolated version\n *  @date Oct 4, 2015\n **/\n\n#pragma once\n\n#include <gpslam/gp/GaussianProcessInterpolatorPose3.h>\n\n#include <gtsam/geometry/Point3.h>\n#include <gtsam/geometry/concepts.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n\n#include <boost/lexical_cast.hpp>\n\n\nnamespace gpslam {\n\n/**\n * Binary factor for an translational measurement like GPS, GP interpolated\n */\nclass GPInterpolatedGPSFactorPose3: public gtsam::NoiseModelFactor4<gtsam::Pose3,\n    gtsam::Vector6, gtsam::Pose3, gtsam::Vector6> {\nprivate:\n\n  // interpolater\n  GaussianProcessInterpolatorPose3 GPbase_;\n\n  gtsam::Point3 measured_; /** measurement */\n  boost::optional<gtsam::Pose3> body_P_sensor_; ///< The pose of the sensor in the body frame\n\n  typedef GPInterpolatedGPSFactorPose3 This;\n  typedef gtsam::NoiseModelFactor4<gtsam::Pose3, gtsam::Vector6, gtsam::Pose3, gtsam::Vector6> Interpolator;\n  typedef GaussianProcessInterpolatorPose3 GPBase;\n\n\npublic:\n\n  /// shorthand for a smart pointer to a factor\n  typedef boost::shared_ptr<This> shared_ptr;\n\n  GPInterpolatedGPSFactorPose3() {} /* Default constructor */\n\n  /**\n   * Constructor\n   * @param body_P_sensor transformation from body to sensor\n   */\n  GPInterpolatedGPSFactorPose3(const gtsam::Point3& measured_point3,\n      const gtsam::SharedNoiseModel& meas_model, const gtsam::SharedNoiseModel& Qc_model,\n      gtsam::Key poseKey1, gtsam::Key velKey1, gtsam::Key poseKey2, gtsam::Key velKey2,\n      double delta_t, double tau, boost::optional<gtsam::Pose3> body_P_sensor = boost::none) :\n        Interpolator(meas_model, poseKey1, velKey1, poseKey2, velKey2),\n        GPbase_(Qc_model, delta_t, tau),\n        measured_(measured_point3), body_P_sensor_(body_P_sensor) {}\n\n  virtual ~GPInterpolatedGPSFactorPose3() {}\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /** factor error */\n  gtsam::Vector evaluateError(const gtsam::Pose3& pose1, const gtsam::Vector6& vel1,\n      const gtsam::Pose3& pose2, const gtsam::Vector6& vel2,\n      boost::optional<gtsam::Matrix&> H1 = boost::none, boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none, boost::optional<gtsam::Matrix&> H4 = boost::none) const {\n\n    using namespace gtsam;\n\n    // interpolate pose\n    Matrix Hint1, Hint2, Hint3, Hint4;\n    Pose3 pose;\n    if (H1 || H2 || H3 || H4)\n      pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2, Hint1, Hint2, Hint3, Hint4);\n    else\n      pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2);\n\n    Matrix Hpose;     // jacobian of pose\n    Point3 point_err;\n\n    if (body_P_sensor_) {\n      Matrix H0;\n      point_err = pose.compose(*body_P_sensor_, H0).translation(Hpose) - measured_;\n      Hpose = Hpose * H0;\n      GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, H1, H2, H3, H4);\n    } else {\n      point_err = pose.translation(Hpose) - measured_;\n      GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, H1, H2, H3, H4);\n    }\n\n    return point_err.vector();\n  }\n\n  /** return the measured */\n  gtsam::Point3 measured() const {\n    return measured_;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e = dynamic_cast<const This*> (&expected);\n    return e != NULL\n        && Base::equals(*e, tol) && GPbase_.equals(e->GPbase_)\n        && (this->measured_ - e->measured_).norm() < tol\n        && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"GPSFactor, point = \" << measured_ << std::endl;\n    if(this->body_P_sensor_)\n      this->body_P_sensor_->print(\"  sensor pose in body frame: \");\n    Base::print(\"\", keyFormatter);\n    GPbase_.print(\"Measurement interpolated at: \");\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(GPbase_);\n    ar & BOOST_SERIALIZATION_NVP(measured_);\n    ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);\n  }\n}; // GPInterpolatedGPSFactorPose3\n\n\n} // namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GPInterpolatedGPSFactorPose3> : public Testable<gpslam::GPInterpolatedGPSFactorPose3> {};\n}\n\n"
  },
  {
    "path": "gpslam/slam/GPInterpolatedGPSFactorPose3VW.h",
    "content": "/**\n *  @file  GPInterpolatedGPSFactorPose3VW.h\n *  @author Jing Dong\n *  @brief Translational measurement like GPS, GP interpolated version\n *  @date Oct 4, 2015\n **/\n\n#pragma once\n\n#include <gpslam/gp/GaussianProcessInterpolatorPose3VW.h>\n\n#include <gtsam/geometry/Point3.h>\n#include <gtsam/geometry/concepts.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n\n#include <boost/lexical_cast.hpp>\n\n\nnamespace gpslam {\n\n/**\n * Binary factor for an translational measurement like GPS, GP interpolated\n */\nclass GPInterpolatedGPSFactorPose3VW: public gtsam::NoiseModelFactor6<gtsam::Pose3,\n    gtsam::Vector3, gtsam::Vector3, gtsam::Pose3, gtsam::Vector3, gtsam::Vector3> {\n\nprivate:\n\n  // interpolater\n  GaussianProcessInterpolatorPose3VW GPbase_;\n\n  gtsam::Point3 measured_; /** measurement */\n  boost::optional<gtsam::Pose3> body_P_sensor_; ///< The pose of the sensor in the body frame\n\n  typedef GPInterpolatedGPSFactorPose3VW This;\n  typedef gtsam::NoiseModelFactor6<gtsam::Pose3, gtsam::Vector3, gtsam::Vector3,\n      gtsam::Pose3, gtsam::Vector3, gtsam::Vector3> Interpolator;\n  typedef GaussianProcessInterpolatorPose3VW GPBase;\n\n\npublic:\n\n  /// shorthand for a smart pointer to a factor\n  typedef boost::shared_ptr<This> shared_ptr;\n\n  GPInterpolatedGPSFactorPose3VW() {} /* Default constructor */\n\n  /**\n   * Constructor\n   * @param body_P_sensor transformation from body to sensor\n   */\n  GPInterpolatedGPSFactorPose3VW(const gtsam::Point3& measured_point3,\n      const gtsam::SharedNoiseModel& meas_model, const gtsam::SharedNoiseModel& Qc_model,\n      gtsam::Key poseKey1, gtsam::Key velKey1, gtsam::Key omegaKey1,\n      gtsam::Key poseKey2, gtsam::Key velKey2, gtsam::Key omegaKey2,\n      double delta_t, double tau, boost::optional<gtsam::Pose3> body_P_sensor = boost::none) :\n        Interpolator(meas_model, poseKey1, velKey1, omegaKey1, poseKey2, velKey2, omegaKey2),\n        GPbase_(Qc_model, delta_t, tau),\n        measured_(measured_point3), body_P_sensor_(body_P_sensor) {\n  }\n\n  virtual ~GPInterpolatedGPSFactorPose3VW() {}\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /** factor error */\n  gtsam::Vector evaluateError(\n      const gtsam::Pose3& pose1, const gtsam::Vector3& vel1, const gtsam::Vector3& omega1,\n      const gtsam::Pose3& pose2, const gtsam::Vector3& vel2, const gtsam::Vector3& omega2,\n      boost::optional<gtsam::Matrix&> H1 = boost::none, boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none, boost::optional<gtsam::Matrix&> H4 = boost::none,\n      boost::optional<gtsam::Matrix&> H5 = boost::none, boost::optional<gtsam::Matrix&> H6 = boost::none) const {\n\n    using namespace gtsam;\n\n    // interpolate pose\n    Matrix Hint1, Hint2, Hint3, Hint4, Hint5, Hint6;\n    Pose3 pose;\n    if (H1 || H2 || H3 || H4 || H5 || H6)\n      pose = GPbase_.interpolatePose(pose1, vel1, omega1, pose2, vel2, omega2,\n          Hint1, Hint2, Hint3, Hint4, Hint5, Hint6);\n    else\n      pose = GPbase_.interpolatePose(pose1, vel1, omega1, pose2, vel2, omega2);\n\n    Matrix Hpose;     // jacobian of pose\n    Point3 point_err;\n\n    if (body_P_sensor_) {\n      Matrix H0;\n      point_err = pose.compose(*body_P_sensor_, H0).translation(Hpose) - measured_;\n      Hpose = Hpose * H0;\n      GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, Hint5, Hint6,\n          H1, H2, H3, H4, H5, H6);\n    } else {\n      point_err = pose.translation(Hpose) - measured_;\n      GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, Hint5, Hint6,\n          H1, H2, H3, H4, H5, H6);\n    }\n\n    return point_err.vector();\n  }\n\n  /** return the measured */\n  gtsam::Point3 measured() const {\n    return measured_;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e = dynamic_cast<const This*> (&expected);\n    return e != NULL\n        && Base::equals(*e, tol) && GPbase_.equals(e->GPbase_)\n        && (this->measured_ - e->measured_).norm() < tol\n        && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"GPSFactor, point = \" << measured_ << std::endl;\n    if(this->body_P_sensor_)\n      this->body_P_sensor_->print(\"  sensor pose in body frame: \");\n    Base::print(\"\", keyFormatter);\n    GPbase_.print(\"Measurement interpolated at: \");\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(GPbase_);\n    ar & BOOST_SERIALIZATION_NVP(measured_);\n    ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);\n  }\n}; // GPInterpolatedGPSFactorPose3VW\n\n} // namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GPInterpolatedGPSFactorPose3VW> : public Testable<gpslam::GPInterpolatedGPSFactorPose3VW> {};\n}\n\n"
  },
  {
    "path": "gpslam/slam/GPInterpolatedProjectionFactorPose3.h",
    "content": "/**\n * @file GPInterpolatedProjectionFactorPose3.h\n * @brief GP Interpolation projection measurement factor for Pose3\n * @author Chris Beall, Richard Roberts, Frank Dellaert, Alex Cunningham\n * @author Jing Dong, Xinyan Yan\n */\n\n#pragma once\n\n#include <gpslam/gp/GaussianProcessInterpolatorPose3.h>\n\n#include <gtsam/nonlinear/NonlinearFactor.h>\n#include <gtsam/geometry/SimpleCamera.h>\n#include <gtsam/geometry/Pose3.h>\n#include <gtsam/geometry/Point3.h>\n\n\nnamespace gpslam {\n\n/**\n * Non-linear factor for a constraint derived from a 2D measurement. The calibration is known here.\n * GP interpolated version\n */\n\ntemplate <class CALIBRATION = gtsam::Cal3_S2>\nclass GPInterpolatedProjectionFactorPose3: public gtsam::NoiseModelFactor5<gtsam::Pose3,\n    gtsam::Vector6, gtsam::Pose3, gtsam::Vector6, gtsam::Point3> {\n\nprotected:\n  // interpolater\n  GaussianProcessInterpolatorPose3 GPbase_;\n\n  // Keep a copy of measurement and calibration for I/O\n  gtsam::Point2 measured_;\t                        ///< 2D measurement\n  boost::shared_ptr<CALIBRATION> K_;        ///< shared pointer to calibration object\n  boost::optional<gtsam::Pose3> body_P_sensor_;    ///< The pose of the sensor in the body frame\n\n  // verbosity handling for Cheirality Exceptions\n  bool throwCheirality_;    ///< If true, rethrows Cheirality exceptions (default: false)\n  bool verboseCheirality_;  ///< If true, prints text for Cheirality exceptions (default: false)\n\n  // typedefs\n  typedef GPInterpolatedProjectionFactorPose3<CALIBRATION> This;\n  typedef gtsam::NoiseModelFactor5<gtsam::Pose3, gtsam::Vector6, gtsam::Pose3,\n      gtsam::Vector6, gtsam::Point3> Base;\n  typedef GaussianProcessInterpolatorPose3 GPBase;\n\npublic:\n\n\n  /// shorthand for a smart pointer to a factor\n  typedef boost::shared_ptr<This> shared_ptr;\n\n  /// Default constructor: do nothing\n  GPInterpolatedProjectionFactorPose3() {}\n\n  /**\n   * Constructor\n   * @param measured is the 2 dimensional location of point in image (the measurement)\n   * @param meas_model is the standard deviation\n   * @param pointKey is the index of the landmark\n   * @param K shared pointer to the constant calibration\n   */\n  GPInterpolatedProjectionFactorPose3(const gtsam::Point2& measured,\n      const gtsam::SharedNoiseModel& cam_model, const gtsam::SharedNoiseModel& Qc_model,\n      gtsam::Key poseKey1, gtsam::Key velKey1, gtsam::Key poseKey2, gtsam::Key velKey2,\n      gtsam::Key pointKey,\n      double delta_t, double tau, const boost::shared_ptr<CALIBRATION>& K,\n      boost::optional<gtsam::Pose3> body_P_sensor = boost::none,\n      bool throwCheirality = false, bool verboseCheirality = false) :\n\n        Base(cam_model, poseKey1, velKey1, poseKey2, velKey2, pointKey),\n        GPbase_(Qc_model, delta_t, tau), measured_(measured), K_(K),\n        body_P_sensor_(body_P_sensor), throwCheirality_(throwCheirality),\n        verboseCheirality_(verboseCheirality){}\n\n  /** Virtual destructor */\n  virtual ~GPInterpolatedProjectionFactorPose3() {}\n\n\n  /// Evaluate error h(x)-z and optionally derivatives\n  gtsam::Vector evaluateError(const gtsam::Pose3& pose1, const gtsam::Vector6& vel1,\n      const gtsam::Pose3& pose2, const gtsam::Vector6& vel2, const gtsam::Point3& point,\n      boost::optional<gtsam::Matrix&> H1 = boost::none, boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none, boost::optional<gtsam::Matrix&> H4 = boost::none,\n      boost::optional<gtsam::Matrix&> H5 = boost::none) const {\n\n    using namespace gtsam;\n\n    // interpolate pose\n    Matrix Hint1, Hint2, Hint3, Hint4;\n    Pose3 pose;\n    if (H1 || H2 || H3 || H4)\n      pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2, Hint1, Hint2, Hint3, Hint4);\n    else\n      pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2);\n\n    // jacobian of pose\n    Matrix Hpose;\n\n    try {\n\n      if (body_P_sensor_) {\n        if (H1 || H2 || H3 || H4) {\n          Matrix H0;\n          PinholeCamera<CALIBRATION> camera(pose.compose(*body_P_sensor_, H0), *K_);\n          Point2 reprojectionError(camera.project(point, Hpose, H5) - measured_);\n          Hpose = Hpose * H0;\n          GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, H1, H2, H3, H4);\n          return reprojectionError.vector();\n        } else {\n          PinholeCamera<CALIBRATION> camera(pose.compose(*body_P_sensor_), *K_);\n          Point2 reprojectionError(camera.project(point, Hpose, H5) - measured_);\n          return reprojectionError.vector();\n        }\n      } else {\n        PinholeCamera<CALIBRATION> camera(pose, *K_);\n        Point2 reprojectionError(camera.project(point, Hpose, H5) - measured_);\n        GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, H1, H2, H3, H4);\n        return reprojectionError.vector();\n      }\n\n    } catch( CheiralityException& e) {\n      // catch CheiralityException\n      if (H1) *H1 = Matrix::Zero(2,6);\n      if (H2) *H2 = Matrix::Zero(2,6);\n      if (H3) *H3 = Matrix::Zero(2,6);\n      if (H4) *H4 = Matrix::Zero(2,6);\n      if (H5) *H5 = Matrix::Zero(2,3);\n      if (verboseCheirality_)\n        std::cout << e.what() << \": Landmark \"<< DefaultKeyFormatter(this->key2()) <<\n            \" moved behind camera \" << DefaultKeyFormatter(this->key1()) << std::endl;\n      if (throwCheirality_)\n        throw e;\n    }\n\n    // no throw case\n    return Vector::Ones(2) * 2.0 * K_->fx();\n  }\n\n  /** return the measurement */\n  const gtsam::Point2& measured() const {\n    return measured_;\n  }\n\n  /** return the calibration object */\n  inline const boost::shared_ptr<CALIBRATION> calibration() const {\n    return K_;\n  }\n\n\n  /**\n   * Testables\n   */\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /**\n   * print\n   * @param s optional string naming the factor\n   * @param keyFormatter optional formatter useful for printing Symbols\n   */\n  void print(const std::string& s = \"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"GPInterpolatedProjectionFactor, z = \"; measured_.print();\n    Base::print(\"\", keyFormatter);\n    GPbase_.print(\"Measurement taken from: \");\n  }\n\n  /// equals\n  virtual bool equals(const gtsam::NonlinearFactor& p, double tol = 1e-9) const {\n    const This *e = dynamic_cast<const This*>(&p);\n    return e && Base::equals(p, tol)\n        && GPbase_.equals(e->GPbase_)\n        && this->measured_.equals(e->measured_, tol)\n        && this->K_->equals(*e->K_, tol)\n        && this->throwCheirality_ == e->throwCheirality_\n        && this->verboseCheirality_ == e->verboseCheirality_;\n  }\n\n\nprivate:\n  /// Serialization function\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(GPbase_);\n    ar & BOOST_SERIALIZATION_NVP(measured_);\n    ar & BOOST_SERIALIZATION_NVP(K_);\n    ar & BOOST_SERIALIZATION_NVP(throwCheirality_);\n    ar & BOOST_SERIALIZATION_NVP(verboseCheirality_);\n  }\n};\n\n\n} // \\ namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<class CALIBRATION>\nstruct traits<gpslam::GPInterpolatedProjectionFactorPose3<CALIBRATION> > :\n    public Testable<gpslam::GPInterpolatedProjectionFactorPose3<CALIBRATION> > {};\n}\n\n\n"
  },
  {
    "path": "gpslam/slam/GPInterpolatedRangeFactor2DLinear.h",
    "content": "/**\n *  @file  GPInterpolatedRangeFactor2DLinear.h\n *  @brief range factor for 2D linear pose, interpolated\n *  @author Jing Dong\n **/\n\n#pragma once\n\n#include <gpslam/gp/GaussianProcessInterpolatorLinear.h>\n\n#include <gtsam/geometry/Point2.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n#include <gtsam/base/Vector.h>\n\n\nnamespace gpslam {\n\n/**\n * Binary factor for range measurement, GP interpolated, 2D linear pose version\n */\nclass GPInterpolatedRangeFactor2DLinear: public gtsam::NoiseModelFactor5<gtsam::Vector3, gtsam::Vector3,\n    gtsam::Vector3, gtsam::Vector3, gtsam::Point2> {\n\nprivate:\n  // interpolater\n  GaussianProcessInterpolatorLinear<3> GPbase_;\n\n  double measured_; /** measurement */\n\n  typedef GPInterpolatedRangeFactor2DLinear This;\n  typedef gtsam::NoiseModelFactor5<gtsam::Vector3, gtsam::Vector3, gtsam::Vector3,\n      gtsam::Vector3, gtsam::Point2> Base;\n  typedef GaussianProcessInterpolatorLinear<3> GPBase;\n\npublic:\n\n  /// shorthand for a smart pointer to a factor\n  typedef boost::shared_ptr<This> shared_ptr;\n\n  GPInterpolatedRangeFactor2DLinear() {} /* Default constructor */\n\n  GPInterpolatedRangeFactor2DLinear(double measured,\n      gtsam::Key pose1Key, gtsam::Key vel1Key, gtsam::Key pose2Key, gtsam::Key vel2Key,\n      gtsam::Key pointKey,\n      const gtsam::SharedNoiseModel& meas_model, const gtsam::SharedNoiseModel& Qc_model,\n      double delta_t, double tau) :\n        Base(meas_model, pose1Key, vel1Key, pose2Key, vel2Key, pointKey),\n        GPbase_(Qc_model, delta_t, tau),\n        measured_(measured) {\n  }\n\n  virtual ~GPInterpolatedRangeFactor2DLinear() {}\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /** factor error */\n  gtsam::Vector evaluateError(const gtsam::Vector3& pose1, const gtsam::Vector3& vel1,\n      const gtsam::Vector3& pose2, const gtsam::Vector3& vel2, const gtsam::Point2& point,\n      boost::optional<gtsam::Matrix&> H1 = boost::none, boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none, boost::optional<gtsam::Matrix&> H4 = boost::none,\n      boost::optional<gtsam::Matrix&> H5 = boost::none) const {\n\n    using namespace gtsam;\n\n    // interpolate pose\n    Matrix3 Hint1, Hint2, Hint3, Hint4;\n    Vector3 pose;\n    if (H1 || H2 || H3 || H4)\n      pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2, Hint1, Hint2, Hint3, Hint4);\n    else\n      pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2);\n\n    Point2 d = point - Point2(pose(0), pose(1));\n    Matrix12 H;\n    double r = d.norm(H);\n\n    Matrix Hpose;\n    if (H1 || H2 || H3 || H4) {\n      Hpose = (Matrix13() << -H, 0.0).finished();\n      GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, H1, H2, H3, H4);\n    }\n\n    if (H5) *H5 = H;\n    return (Vector(1) << r - measured_).finished();\n  }\n\n  /** return the measured */\n  double measured() const {\n    return measured_;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e = dynamic_cast<const This*> (&expected);\n    return e != NULL && Base::equals(*e, tol)\n        && fabs(this->measured_ - e->measured_) < tol;\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"RangeFactor, range = \" << measured_ << std::endl;\n    Base::print(\"\", keyFormatter);\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(measured_);\n  }\n\n}; // GPInterpolatedRangeFactor2DLinear\n\n\n} // namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GPInterpolatedRangeFactor2DLinear> : public Testable<gpslam::GPInterpolatedRangeFactor2DLinear> {};\n}\n\n"
  },
  {
    "path": "gpslam/slam/GPInterpolatedRangeFactorPose2.h",
    "content": "/**\n *  @file  GPInterpolatedRangeFactorPose2.H\n *  @brief range factor for SE(2) pose, interpolated\n *  @author Jing Dong\n **/\n\n#pragma once\n\n#include <gpslam/gp/GaussianProcessInterpolatorPose2.h>\n\n#include <gtsam/geometry/Pose2.h>\n#include <gtsam/geometry/concepts.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n\n#include <boost/lexical_cast.hpp>\n\n\nnamespace gpslam {\n\n/**\n * Binary factor for range measurement, GP interpolated, SE(2) pose version\n */\nclass GPInterpolatedRangeFactorPose2: public gtsam::NoiseModelFactor5<gtsam::Pose2,\n    gtsam::Vector3, gtsam::Pose2, gtsam::Vector3, gtsam::Point2> {\n\nprivate:\n  // interpolater\n  GaussianProcessInterpolatorPose2 GPbase_;\n\n  double measured_; /** measurement */\n  boost::optional<gtsam::Pose2> body_P_sensor_; ///< The pose of the sensor in the body frame\n\n  typedef GPInterpolatedRangeFactorPose2 This;\n  typedef gtsam::NoiseModelFactor5<gtsam::Pose2, gtsam::Vector3, gtsam::Pose2,\n      gtsam::Vector3, gtsam::Point2> Base;\n  typedef GaussianProcessInterpolatorPose2 GPBase;\n\n\npublic:\n\n  /// shorthand for a smart pointer to a factor\n  typedef boost::shared_ptr<This> shared_ptr;\n\n  GPInterpolatedRangeFactorPose2() {} /* Default constructor */\n\n  GPInterpolatedRangeFactorPose2(double measured,\n      const gtsam::SharedNoiseModel& meas_model, const gtsam::SharedNoiseModel& Qc_model,\n      gtsam::Key poseKey1, gtsam::Key velKey1, gtsam::Key poseKey2, gtsam::Key velKey2,\n      gtsam::Key pointKey,\n      double delta_t, double tau, boost::optional<gtsam::Pose2> body_P_sensor = boost::none) :\n        Base(meas_model, poseKey1, velKey1, poseKey2, velKey2, pointKey),\n        GPbase_(Qc_model, delta_t, tau),\n        measured_(measured), body_P_sensor_(body_P_sensor) {\n  }\n\n  virtual ~GPInterpolatedRangeFactorPose2() {}\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /** factor error */\n  gtsam::Vector evaluateError(const gtsam::Pose2& pose1, const gtsam::Vector3& vel1,\n      const gtsam::Pose2& pose2, const gtsam::Vector3& vel2, const gtsam::Point2& point,\n      boost::optional<gtsam::Matrix&> H1 = boost::none, boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none, boost::optional<gtsam::Matrix&> H4 = boost::none,\n      boost::optional<gtsam::Matrix&> H5 = boost::none) const {\n\n    using namespace gtsam;\n\n    // interpolate pose\n    Matrix3 Hint1, Hint2, Hint3, Hint4;\n    Pose2 pose;\n    if (H1 || H2 || H3 || H4)\n      pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2, Hint1, Hint2, Hint3, Hint4);\n    else\n      pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2);\n\n    Matrix Hpose;     // jacobian of pose\n    double hx;      // measure\n\n    if (body_P_sensor_) {\n      if (H1 || H2 || H3 || H4) {\n        Matrix H0;\n        hx = pose.compose(*body_P_sensor_, H0).range(point, Hpose, H5);\n        Hpose = Hpose * H0;\n        GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, H1, H2, H3, H4);\n      } else {\n        hx = pose.compose(*body_P_sensor_).range(point, Hpose, H5);\n      }\n    } else {\n      hx = pose.range(point, Hpose, H5);\n      GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, H1, H2, H3, H4);\n    }\n\n    return (Vector(1) << hx - measured_).finished();\n  }\n\n  /** return the measured */\n  double measured() const {\n    return measured_;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e = dynamic_cast<const This*> (&expected);\n    return e != NULL\n        && Base::equals(*e, tol)\n    && this->GPbase_.equals(e->GPbase_)\n    && fabs(this->measured_ - e->measured_) < tol\n    && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"RangeFactor, range = \" << measured_ << std::endl;\n    if(this->body_P_sensor_)\n      this->body_P_sensor_->print(\"Sensor pose in body frame: \");\n    Base::print(\"\", keyFormatter);\n    GPbase_.print(\"Measurement taken from: \");\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & boost::serialization::make_nvp(\"NoiseModelFactor5\",\n        boost::serialization::base_object<Base>(*this));\n    ar & BOOST_SERIALIZATION_NVP(GPbase_);\n    ar & BOOST_SERIALIZATION_NVP(measured_);\n    ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);\n  }\n}; // GPInterpolatedRangeFactorPose2\n\n\n} // namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GPInterpolatedRangeFactorPose2> : public Testable<gpslam::GPInterpolatedRangeFactorPose2> {};\n}\n\n"
  },
  {
    "path": "gpslam/slam/GPInterpolatedRangeFactorPose3.h",
    "content": "/**\n *  @file  GPInterpolatedRangeFactorPose3.H\n *  @brief range factor for SE(3) pose, interpolated\n *  @author Frank Dellaert, Jing Dong\n **/\n\n#pragma once\n\n#include <gpslam/gp/GaussianProcessInterpolatorPose3.h>\n\n#include <gtsam/geometry/Pose3.h>\n#include <gtsam/geometry/concepts.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n\n#include <boost/lexical_cast.hpp>\n\n\nnamespace gpslam {\n\n/**\n * Binary factor for range measurement, GP interpolated, SE(3) pose version\n */\nclass GPInterpolatedRangeFactorPose3: public gtsam::NoiseModelFactor5<gtsam::Pose3,\n    gtsam::Vector6, gtsam::Pose3, gtsam::Vector6, gtsam::Point3> {\n\nprivate:\n  // interpolater\n  GaussianProcessInterpolatorPose3 GPbase_;\n\n  double measured_; /** measurement */\n  boost::optional<gtsam::Pose3> body_P_sensor_; ///< The pose of the sensor in the body frame\n\n  typedef GPInterpolatedRangeFactorPose3 This;\n  typedef gtsam::NoiseModelFactor5<gtsam::Pose3, gtsam::Vector6, gtsam::Pose3, gtsam::Vector6,\n      gtsam::Point3> Base;\n  typedef GaussianProcessInterpolatorPose3 GPBase;\n\n\npublic:\n\n  /// shorthand for a smart pointer to a factor\n  typedef boost::shared_ptr<This> shared_ptr;\n\n  GPInterpolatedRangeFactorPose3() {} /* Default constructor */\n\n  GPInterpolatedRangeFactorPose3(double measured,\n      const gtsam::SharedNoiseModel& meas_model, const gtsam::SharedNoiseModel& Qc_model,\n      gtsam::Key poseKey1, gtsam::Key velKey1, gtsam::Key poseKey2, gtsam::Key velKey2,\n      gtsam::Key pointKey,\n      double delta_t, double tau, boost::optional<gtsam::Pose3> body_P_sensor = boost::none) :\n        Base(meas_model, poseKey1, velKey1, poseKey2, velKey2, pointKey),\n        GPbase_(Qc_model, delta_t, tau),\n        measured_(measured), body_P_sensor_(body_P_sensor) {\n  }\n\n  virtual ~GPInterpolatedRangeFactorPose3() {}\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /** factor error */\n  gtsam::Vector evaluateError(const gtsam::Pose3& pose1, const gtsam::Vector6& vel1,\n      const gtsam::Pose3& pose2, const gtsam::Vector6& vel2, const gtsam::Point3& point,\n      boost::optional<gtsam::Matrix&> H1 = boost::none, boost::optional<gtsam::Matrix&> H2 = boost::none,\n      boost::optional<gtsam::Matrix&> H3 = boost::none, boost::optional<gtsam::Matrix&> H4 = boost::none,\n      boost::optional<gtsam::Matrix&> H5 = boost::none) const {\n\n    using namespace gtsam;\n\n    // interpolate pose\n    Matrix Hint1, Hint2, Hint3, Hint4;\n    Pose3 pose;\n    if (H1 || H2 || H3 || H4)\n      pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2, Hint1, Hint2, Hint3, Hint4);\n    else\n      pose = GPbase_.interpolatePose(pose1, vel1, pose2, vel2);\n\n    Matrix Hpose;     // jacobian of pose\n    double hx;      // measure\n\n    if (body_P_sensor_) {\n      if (H1 || H2 || H3 || H4) {\n        Matrix H0;\n        hx = pose.compose(*body_P_sensor_, H0).range(point, Hpose, H5);\n        Hpose = Hpose * H0;\n        GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, H1, H2, H3, H4);\n      } else {\n        hx = pose.compose(*body_P_sensor_).range(point, Hpose, H5);\n      }\n    } else {\n      hx = pose.range(point, Hpose, H5);\n      GPBase::updatePoseJacobians(Hpose, Hint1, Hint2, Hint3, Hint4, H1, H2, H3, H4);\n    }\n\n    return (Vector(1) << hx - measured_).finished();\n  }\n\n  /** return the measured */\n  double measured() const {\n    return measured_;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e = dynamic_cast<const This*> (&expected);\n    return e != NULL\n        && Base::equals(*e, tol)\n    && this->GPbase_.equals(e->GPbase_)\n    && fabs(this->measured_ - e->measured_) < tol\n    && ((!body_P_sensor_ && !e->body_P_sensor_) || (body_P_sensor_ && e->body_P_sensor_ && body_P_sensor_->equals(*e->body_P_sensor_)));\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"RangeFactor, range = \" << measured_ << std::endl;\n    if(this->body_P_sensor_)\n      this->body_P_sensor_->print(\"Sensor pose in body frame: \");\n    Base::print(\"\", keyFormatter);\n    GPbase_.print(\"Measurement taken from: \");\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & boost::serialization::make_nvp(\"NoiseModelFactor5\",\n        boost::serialization::base_object<Base>(*this));\n    ar & BOOST_SERIALIZATION_NVP(GPbase_);\n    ar & BOOST_SERIALIZATION_NVP(measured_);\n    ar & BOOST_SERIALIZATION_NVP(body_P_sensor_);\n  }\n}; // GPInterpolatedRangeFactorPose3\n\n\n} // namespace gpslam\n\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::GPInterpolatedRangeFactorPose3> : public Testable<gpslam::GPInterpolatedRangeFactorPose3> {};\n}\n\n"
  },
  {
    "path": "gpslam/slam/OdometryFactor2DLinear.h",
    "content": "/**\n*  @file  OdometryFactor2DLinear.H\n*  @brief 2-way odometry factor, 2D linear pose version\n*  @author Xinyan Yan, Jing Dong\n*/\n\n\n#pragma once\n\n#include <gtsam/geometry/concepts.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/Lie.h>\n#include <gtsam/geometry/Pose2.h>\n\n#include <ostream>\n\n\nnamespace gpslam {\n\n/**\n * 2-way odometry factor, 2D linear pose version\n */\nclass OdometryFactor2DLinear: public gtsam::NoiseModelFactor2<gtsam::Vector3, gtsam::Vector3> {\n\nprivate:\n  gtsam::Vector3 measured_; /** measurement  distdot, 0, thetadot */\n  typedef OdometryFactor2DLinear This;\n  typedef gtsam::NoiseModelFactor2<gtsam::Vector3, gtsam::Vector3> Base;\n\npublic:\n\n  OdometryFactor2DLinear() {}  /* Default constructor */\n\n  /**\n   * @param betweenMeasured odometry measurement [dx dy dtheta] in body frame\n   */\n  OdometryFactor2DLinear(gtsam::Key pose1Key, gtsam::Key pose2Key, const gtsam::Vector3& betweenMeasured,\n      const gtsam::SharedNoiseModel& model) :\n    Base(model, pose1Key, pose2Key), measured_(betweenMeasured) {}\n\n  virtual ~OdometryFactor2DLinear() {}\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  // Calculate error and Jacobians\n  gtsam::Vector evaluateError(const gtsam::Vector3& pose1, const gtsam::Vector3& pose2,\n      boost::optional<gtsam::Matrix&> H1 = boost::none,\n      boost::optional<gtsam::Matrix&> H2 = boost::none) const {\n\n    using namespace gtsam;\n\n    Vector3 vec_diff = pose2 - pose1;\n\n    Point2 point_diff_local;\n    if (H1 || H2) {\n      Matrix Hrot, Hp;\n      point_diff_local = Rot2(pose1(2)).unrotate(Point2(vec_diff(0), vec_diff(1)), Hrot, Hp);\n\n      // compute Jacobian\n      if (H1) *H1 = (Matrix3() << -Hp, Hrot, Matrix12::Zero(), -1).finished();\n      if (H2) *H2 = (Matrix3() << Hp, Matrix21::Zero(), Matrix12::Zero(), 1).finished();\n\n    } else {\n      point_diff_local = Rot2(pose1(2)).unrotate(Point2(vec_diff(0), vec_diff(1)));\n\n    }\n    return (Vector(3) << point_diff_local.x() - measured_(0),\n        point_diff_local.y() - measured_(1),\n        vec_diff(2) - measured_(2)).finished();\n\n  }\n\n\n  /** return the measured */\n  const gtsam::Vector3& measured() const {\n    return measured_;\n  }\n\n  /** number of variables attached to this factor */\n  size_t size() const {\n    return 2;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e =  dynamic_cast<const This*> (&expected);\n    return e != NULL && Base::equals(*e, tol)\n        && gtsam::equal_with_abs_tol(this->measured_, e->measured_, tol);\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"2-way projected odometry factor\" << std::endl;\n    Base::print(\"\", keyFormatter);\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & boost::serialization::make_nvp(\"NoiseModelFactor2\",\n        boost::serialization::base_object<Base>(*this));\n    ar & BOOST_SERIALIZATION_NVP(measured_);\n  }\n}; // OdometryFactor2DLinear\n\n} // namespace gpslam\n\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::OdometryFactor2DLinear> : public Testable<gpslam::OdometryFactor2DLinear> {};\n}\n\n\n"
  },
  {
    "path": "gpslam/slam/RangeBearingFactor2DLinear.h",
    "content": "/**\n *  @file  RangeBearingFactor2DLinear.h\n *  @brief range + bearing factor for 2D linear pose\n *  @author Xinyan Yan, Jing Dong\n *  @date  Nov 3, 2015\n **/\n\n#pragma once\n\n#include <gtsam/geometry/Pose2.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n#include <gtsam/base/Vector.h>\n\nnamespace gpslam {\n\n/**\n * range and bearing measurement, 2D linear pose version\n */\nclass RangeBearingFactor2DLinear: public gtsam::NoiseModelFactor2<gtsam::Vector3, gtsam::Point2> {\nprivate:\n\n  // measurements\n  double range_;\n  gtsam::Rot2 bearing_;\n\n  typedef RangeBearingFactor2DLinear This;\n  typedef gtsam::NoiseModelFactor2<gtsam::Vector3, gtsam::Point2> Base;\n\npublic:\n\n  RangeBearingFactor2DLinear() {} /* Default constructor */\n\n  RangeBearingFactor2DLinear(gtsam::Key poseKey, gtsam::Key pointKey,\n      double range, const gtsam::Rot2& bearing,\n      const gtsam::SharedNoiseModel& model) :\n        Base(model, poseKey, pointKey), range_(range), bearing_(bearing) {\n  }\n\n  virtual ~RangeBearingFactor2DLinear() {}\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /** h(x)-z */\n  gtsam::Vector evaluateError(const gtsam::Vector3& pose, const gtsam::Point2& point,\n      boost::optional<gtsam::Matrix&> H1 = boost::none,\n      boost::optional<gtsam::Matrix&> H2 = boost::none) const {\n\n    using namespace gtsam;\n\n    Pose2 pose2(pose(0), pose(1), pose(2));\n    Point2 rel_point = pose2.transform_to(point);\n    Rot2 expect_rot = Rot2::atan2(rel_point.y(), rel_point.x());\n    Matrix12 Hnorm;\n    double expect_d = Point2(point - pose2.t()).norm(Hnorm);\n\n    // jacobians\n    if (H1 || H2) {\n      Matrix12 tmp;\n      if (expect_d > 1e-5) {\n        double expect_d2 = expect_d * expect_d;\n        tmp = (Matrix12() << -rel_point.y()/expect_d2, rel_point.x()/expect_d2).finished();\n      } else {\n        tmp = Matrix12::Zero();\n      }\n      Matrix13 H11, H21;\n      Matrix12 H12, H22;\n      if (H1) {\n        Vector2 t(rel_point.y(), -rel_point.x());\n        H11 = tmp * (Matrix23() << -pose2.r().transpose(), t).finished();\n        H21 = (Matrix13() << -Hnorm, 0.0).finished();\n        *H1 = (Matrix23() << H11, H21).finished();\n      }\n      if (H2) {\n        H12 = tmp * pose2.r().transpose();\n        H22 = Hnorm;\n        *H2 = (Matrix2() << H12, H22).finished();\n      }\n    }\n\n    return (Vector(2) << Rot2::Logmap(bearing_.between(expect_rot)), expect_d - range_).finished();\n  }\n\n  /** return the measured */\n  double range() const {\n    return range_;\n  }\n  const gtsam::Rot2& bearing() const {\n    return bearing_;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e = dynamic_cast<const This*> (&expected);\n    return e != NULL && Base::equals(*e, tol)\n        && fabs(this->range_ - e->range_) < tol\n        && this->bearing_.equals(e->bearing_, tol);\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"RangeBearingFactor, range = \" << range_\n        << \", bearing = \"; bearing_.print();\n    Base::print(\"\", keyFormatter);\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(range_);\n    ar & BOOST_SERIALIZATION_NVP(bearing_);\n  }\n\n}; // RangeBearingFactor2DLinear\n\n} // namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::RangeBearingFactor2DLinear> : public Testable<gpslam::RangeBearingFactor2DLinear> {};\n}\n\n"
  },
  {
    "path": "gpslam/slam/RangeFactor2DLinear.h",
    "content": "/**\n *  @file  RangeFactor2DLinear.h\n *  @brief range factor for 2D linear pose\n *  @author Xinyan Yan, Jing Dong\n **/\n\n#pragma once\n\n#include <gtsam/geometry/Point2.h>\n#include <gtsam/nonlinear/NonlinearFactor.h>\n#include <gtsam/base/Vector.h>\n\n\nnamespace gpslam {\n\n/**\n * range measurement, 2D linear pose version\n */\nclass RangeFactor2DLinear: public gtsam::NoiseModelFactor2<gtsam::Vector3, gtsam::Point2> {\nprivate:\n\n  double measured_; /** measurement */\n  typedef RangeFactor2DLinear This;\n  typedef gtsam::NoiseModelFactor2<gtsam::Vector3, gtsam::Point2> Base;\n\npublic:\n\n  RangeFactor2DLinear() {} /* Default constructor */\n\n  RangeFactor2DLinear(gtsam::Key poseKey, gtsam::Key pointKey, double measured,\n      const gtsam::SharedNoiseModel& model) :\n        Base(model, poseKey, pointKey), measured_(measured) {\n  }\n\n  virtual ~RangeFactor2DLinear() {}\n\n  /// @return a deep copy of this factor\n  virtual gtsam::NonlinearFactor::shared_ptr clone() const {\n    return boost::static_pointer_cast<gtsam::NonlinearFactor>(\n        gtsam::NonlinearFactor::shared_ptr(new This(*this))); }\n\n  /** h(x)-z */\n  gtsam::Vector evaluateError(const gtsam::Vector3& pose, const gtsam::Point2& point,\n      boost::optional<gtsam::Matrix&> H1 = boost::none,\n      boost::optional<gtsam::Matrix&> H2 = boost::none) const {\n\n    using namespace gtsam;\n\n    Point2 d = point - Point2(pose(0), pose(1));\n    Matrix12 H;\n    double r = d.norm(H);\n\n    if(H1) *H1 = (Matrix13() << -H, 0.0).finished();\n    if(H2) *H2 = H;\n    return (Vector(1) << r - measured_).finished();\n  }\n\n  /** return the measured */\n  double measured() const {\n    return measured_;\n  }\n\n  /** equals specialized to this factor */\n  virtual bool equals(const gtsam::NonlinearFactor& expected, double tol=1e-9) const {\n    const This *e = dynamic_cast<const This*> (&expected);\n    return e != NULL && Base::equals(*e, tol)\n        && fabs(this->measured_ - e->measured_) < tol;\n  }\n\n  /** print contents */\n  void print(const std::string& s=\"\", const gtsam::KeyFormatter& keyFormatter = gtsam::DefaultKeyFormatter) const {\n    std::cout << s << \"RangeFactor, range = \" << measured_ << std::endl;\n    Base::print(\"\", keyFormatter);\n  }\n\nprivate:\n\n  /** Serialization function */\n  friend class boost::serialization::access;\n  template<class ARCHIVE>\n  void serialize(ARCHIVE & ar, const unsigned int version) {\n    ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);\n    ar & BOOST_SERIALIZATION_NVP(measured_);\n  }\n\n}; // RangeFactor2DLinear\n\n} // namespace gpslam\n\n\n/// traits\nnamespace gtsam {\ntemplate<>\nstruct traits<gpslam::RangeFactor2DLinear> : public Testable<gpslam::RangeFactor2DLinear> {};\n}\n\n"
  },
  {
    "path": "gpslam/slam/RangeFactorPose2.h",
    "content": "/**\n *  @file  RangeFactorPose2.h\n *  @brief range factor pose2\n *  @author Jing Dong\n **/\n\n#pragma once\n\n#include <gtsam/geometry/Pose2.h>\n#include <gtsam/geometry/Point2.h>\n#include <gtsam/sam/RangeFactor.h>\n\nnamespace gpslam {\n\ntypedef gtsam::RangeFactor<gtsam::Pose2, gtsam::Point2, double> RangeFactorPose2;\n\n} // namespace gpslam\n"
  },
  {
    "path": "gpslam/slam/tests/testGPInterpolatedGPSFactorPose3.cpp",
    "content": "/**\n*  @file testGPInterpolatedGPSFactorPose3.cpp\n*  @author Jing Dong\n*  @date Oct 4, 2015\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/slam/GPInterpolatedGPSFactorPose3.h>\n#include <gpslam/gp/GaussianProcessPriorPose3.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\ntypedef GPInterpolatedGPSFactorPose3 GPSFactor;\n\n// error function wrapper for bind 10 params, by ignore default boost::none\ninline Vector errorWrapper(const GPSFactor& factor,\n    const Pose3& pose1, const Vector6& vel1,\n    const Pose3& pose2, const Vector6& vel2) {\n  return factor.evaluateError(pose1, vel1, pose2, vel2);\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedGPSFactorPose3, error) {\n\n  noiseModel::Isotropic::shared_ptr model_range =\n      noiseModel::Isotropic::Sigma(3, 0.1);\n  Matrix Qc = 0.001 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.04;\n  Pose3 body_T_sensor = Pose3(Rot3::Ypr(1.0, 0.4, 0.5), Point3(0.3, 0.6, -0.7));\n  Pose3 p1, p2;\n  Vector6 v1, v2;\n  Point3 gps_meas;\n  GPSFactor factor;\n  Vector expect, actual;\n  Matrix expectH1, expectH2, expectH3, expectH4;\n  Matrix actualH1, actualH2, actualH3, actualH4;\n\n  // test at origin, land is in front of z\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 0, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 0, 0, 0).finished();\n  gps_meas = Point3(0, 0, 0);\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Vector::Zero(3);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1)), v2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // interpolat at origin: forward velocity\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(-0.04, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.06, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  gps_meas = Point3(0, 0, 0);\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Vector::Zero(3);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1)), v2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // interpolat at origin: rotate\n  p1 = Pose3(Rot3::Ypr(-0.04, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0.06, 0, 0), Point3(0, 0, 0));\n  v1 = (Vector6() << 0, 0, 1, 0, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 1, 0, 0, 0).finished();\n  gps_meas = Point3(0, 0, 0);\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Vector::Zero(3);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1)), v2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // forward velocity with body_P_sensor\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(1.5, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 15, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 15, 0, 0).finished();\n  // ground truth pose:\n  Pose3 ture_pose = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.6, 0, 0));\n  gps_meas = (ture_pose.compose(body_T_sensor)).translation();\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, dt, tau, body_T_sensor);\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expect = Vector::Zero(3);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1)), v2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n\n\n  // some random stuff: just for test jacobians\n  p1 = Pose3(Rot3::Ypr(1.3, 2.4, 1.2), Point3(0.2, 0.3, 0.4));\n  p2 = Pose3(Rot3::Ypr(0.5, 6.5, 1.1), Point3(1.5, 0.7, 0.5));\n  v1 = (Vector6() << 1.0, 2.0, 0.4, 15, 0.3, 0.2).finished();\n  v2 = (Vector6() << 2.0, 0.2, 0.1, 17, 0.4, 0.7).finished();\n  // ground truth pose:\n  gps_meas = Point3(0, 0, 0);\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, dt, tau, body_T_sensor);\n  actual = factor.evaluateError(p1, v1, p2, v2, actualH1, actualH2,\n      actualH3, actualH4);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1)), v2, 1e-4);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedGPSFactorPose3, optimization) {\n  /**\n   * A simple graph:\n   *\n   *  gps1,2,3\n   *  /  \\\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   * |   |\n   * pv1 pv2\n   *\n   * p1 and p2 are constrained by GP prior and measurement, velcity is known.\n   * 3 measurements are given in different places (on a line)\n   */\n\n  noiseModel::Isotropic::shared_ptr model_prior =  noiseModel::Isotropic::Sigma(6, 0.01);\n  noiseModel::Isotropic::shared_ptr model_prior_loss =  noiseModel::Isotropic::Sigma(6, 100);\n  noiseModel::Isotropic::shared_ptr model_gps =  noiseModel::Isotropic::Sigma(3, 0.1);\n  double delta_t = 0.1, tau1 = -0.1, tau2 = 0.05, tau3 = 0.2;\n  Matrix Qc = 0.01 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  // ground truth\n  Pose3 p1(Rot3(), Point3(0,0,0)), p2(Rot3(), Point3(1,0,0));\n  Pose3 pcam1(Rot3(), Point3(-1,0,0)), pcam2(Rot3(), Point3(0.5,0,0)),\n      pcam3(Rot3(), Point3(2,0,0));\n  Vector6 v1 = (Vector6() << 0, 0, 0, 10, 0, 0).finished();\n  Vector6 v2 = (Vector6() << 0, 0, 0, 10, 0, 0).finished();\n\n  // init values\n  Pose3 p1i(Rot3::Ypr(0.1, 0.1, -0.1), Point3(0.04, 0.1, -0.06));\n  Pose3 p2i(Rot3::Ypr(-0.1, 0.1, -0.1), Point3(1.05, -0.1, 0.1));\n  Vector6 v1i = (Vector6() << -0.1, 0, 0, 9.8, 0, 0.2).finished();\n  Vector6 v2i = (Vector6() << 0, 0, 0.2, 9.7, 0, -0.1).finished();\n\n  // landmark and measurements\n  Point3 meas1 = pcam1.translation();\n  Point3 meas2 = pcam2.translation();\n  Point3 meas3 = pcam3.translation();\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Pose3>(Symbol('x', 1), p1, model_prior_loss));\n  //graph.add(PriorFactor<Pose3>(Symbol('x', 2), p2, model_prior_loss));\n  graph.add(PriorFactor<Vector6>(Symbol('v', 1), v1, model_prior));\n  graph.add(PriorFactor<Vector6>(Symbol('v', 2), v2, model_prior));\n  graph.add(GaussianProcessPriorPose3(Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, Qc_model));\n  graph.add(GPSFactor(meas1, model_gps, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, tau1));\n  graph.add(GPSFactor(meas2, model_gps, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, tau2));\n  graph.add(GPSFactor(meas3, model_gps, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, tau3));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), p1i);\n  init_values.insert(Symbol('v', 1), v1i);\n  init_values.insert(Symbol('x', 2), p2i);\n  init_values.insert(Symbol('v', 2), v2i);\n\n  GaussNewtonParams parameters;\n  parameters.setVerbosity(\"ERROR\");\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(p1, values.at<Pose3>(Symbol('x', 1)), 1e-6));\n  EXPECT(assert_equal(p2, values.at<Pose3>(Symbol('x', 2)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector6>(Symbol('v', 1)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector6>(Symbol('v', 2)), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/slam/tests/testGPInterpolatedGPSFactorPose3VW.cpp",
    "content": "/**\n*  @file testGPInterpolatedGPSFactorPose3VW.cpp\n*  @author Jing Dong\n*  @date Nov 21, 2015\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/slam/GPInterpolatedGPSFactorPose3VW.h>\n#include <gpslam/gp/GaussianProcessPriorPose3VW.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\ntypedef GPInterpolatedGPSFactorPose3VW GPSFactor;\n\n// error function wrapper for bind 10 params, by ignore default boost::none\ninline Vector errorWrapper(const GPSFactor& factor,\n    const Pose3& pose1, const Vector3& vel1, const Vector3& omg1,\n    const Pose3& pose2, const Vector3& vel2, const Vector3& omg2) {\n  return factor.evaluateError(pose1, vel1, omg1, pose2, vel2, omg2);\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedGPSFactorPose3VW, error) {\n\n  noiseModel::Isotropic::shared_ptr model_range =\n      noiseModel::Isotropic::Sigma(3, 0.1);\n  Matrix Qc = 0.001 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.04;\n  Pose3 body_T_sensor = Pose3(Rot3::Ypr(1.4, 4.4, -0.5), Point3(0.3, 0.6, -0.7));\n  Pose3 body_T_sensor_rotonly = Pose3(Rot3::Ypr(1.4, 4.4, -0.5), Point3(0, 0, 0));\n  Pose3 p1, p2;\n  Vector3 v1, v2, w1, w2;\n  Point3 gps_meas;\n  GPSFactor factor;\n  Vector expect, actual;\n  Matrix expectH1, expectH2, expectH3, expectH4, expectH5, expectH6;\n  Matrix actualH1, actualH2, actualH3, actualH4, actualH5, actualH6;\n\n  // test at origin, land is in front of z\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  v1 = Vector3(0, 0, 0); w1 = Vector3(0, 0, 0);\n  v2 = Vector3(0, 0, 0); w2 = Vector3(0, 0, 0);\n  gps_meas = Point3(0, 0, 0);\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expect = Vector::Zero(3);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-6);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n\n  // interpolat at origin: forward velocity\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(-0.04, 0.04, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.06, -0.06, 0));\n  v1 = Vector3(1, -1, 0); w1 = Vector3(0, 0, 0);\n  v2 = Vector3(1, -1, 0); w2 = Vector3(0, 0, 0);\n  gps_meas = Point3(0, 0, 0);\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expect = Vector::Zero(3);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-4);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n\n  // interpolat at origin: rotate\n  p1 = Pose3(Rot3::Ypr(-0.04, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0.06, 0, 0), Point3(0, 0, 0));\n  v1 = Vector3(0, 0, 0); w1 = Vector3(0, 0, 1);\n  v2 = Vector3(0, 0, 0); w2 = Vector3(0, 0, 1);\n  gps_meas = Point3(0, 0, 0);\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expect = Vector::Zero(3);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-6);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n\n  // forward velocity with body_P_sensor\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(1, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(2.5, 0.5, 0));\n  v1 = Vector3(15, 5, 0); w1 = Vector3(0, 0, 0);\n  v2 = Vector3(15, 5, 0); w2 = Vector3(0, 0, 0);\n  // ground truth pose\n  Pose3 ture_pose = Pose3(Rot3::Ypr(0, 0.0, 0.0), Point3(1.6, 0.2, 0));\n  gps_meas = (ture_pose.compose(body_T_sensor)).translation();\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, 0, 0, dt, tau, body_T_sensor);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expect = Vector::Zero(3);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-4);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n  // forward velocity with body_P_sensor_rotonly\n  // test non-zero error\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(1, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(2.5, 0.5, 0));\n  v1 = Vector3(15, 5, 0); w1 = Vector3(0, 0, 0);\n  v2 = Vector3(15, 5, 0); w2 = Vector3(0, 0, 0);\n  // ground truth pose\n  gps_meas = Point3(0, 0, 0);\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, 0, 0, dt, tau, body_T_sensor_rotonly);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expect = Vector3(1.6, 0.2, 0);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-4);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n\n  // rotate with body_P_sensor\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(1.0, 0, 0), Point3(0, 0, 0));\n  v1 = Vector3(0, 0, 0); w1 = Vector3(0, 0, 10);\n  v2 = Vector3(0, 0, 0); w2 = Vector3(0, 0, 10);\n  // ground truth pose\n  ture_pose = Pose3(Rot3::Ypr(0.4, 0.0, 0.0), Point3(0, 0, 0));\n  gps_meas = (ture_pose.compose(body_T_sensor)).translation();\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, 0, 0, dt, tau, body_T_sensor);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expect = Vector::Zero(3);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-4);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n\n  // some random stuff: just for test jacobians\n  p1 = Pose3(Rot3::Ypr(0.4, -0.8, 0.2), Point3(3, -8, 2));\n  p2 = Pose3(Rot3::Ypr(0.1, 0.3, -0.5), Point3(-9, 3, 4));\n  v1 = Vector3(0.1, -0.2, -1.4); w1 = Vector3(0.5, 0.9, 0.7);\n  v1 = Vector3(0.6, 0.3, -0.9); w1 = Vector3(0.4, -0.2, 0.8);\n  // ground truth pose:\n  gps_meas = Point3(0, 0, 0);\n  factor = GPSFactor(gps_meas, model_range, Qc_model, 0, 0, 0, 0, 0, 0, dt, tau, body_T_sensor);\n  actual = factor.evaluateError(p1, v1, w1, p2, v2, w2, actualH1, actualH2,\n      actualH3, actualH4, actualH5, actualH6);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, w1, p2, v2, w2)), p1, 1e-8);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, w1, p2, v2, w2)), v1, 1e-8);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, p2, v2, w2)), w1, 1e-8);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, _1, v2, w2)), p2, 1e-8);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, _1, w2)), v2, 1e-8);\n  expectH6 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, w1, p2, v2, _1)), w2, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n  EXPECT(assert_equal(expectH6, actualH6, 1e-6));\n\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedGPSFactorPose3VW, optimization) {\n  /**\n   * A simple graph:\n   *\n   *  gps1,2,3\n   *  /  \\\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   * |   |\n   * pv1 pv2\n   *\n   * p1 and p2 are constrained by GP prior and measurement, velcity is known.\n   * 3 measurements are given in different places (on a line)\n   */\n\n  noiseModel::Isotropic::shared_ptr model_prior =  noiseModel::Isotropic::Sigma(6, 0.1);\n  noiseModel::Isotropic::shared_ptr model_prior_loss =  noiseModel::Isotropic::Sigma(6, 100);\n  noiseModel::Isotropic::shared_ptr model_gps =  noiseModel::Isotropic::Sigma(3, 0.01);\n  double delta_t = 0.1, tau1 = -0.1, tau2 = 0.05, tau3 = 0.2;\n  Matrix Qc = 0.01 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  // ground truth\n  Pose3 p1(Rot3(), Point3(0,0,0)), p2(Rot3(), Point3(1,0,0));\n  Pose3 pcam1(Rot3(), Point3(-1,0,0)), pcam2(Rot3(), Point3(0.5,0,0)),\n      pcam3(Rot3(), Point3(2,0,0));\n  Vector3 v1 = Vector3(10, 0, 0), w1 = Vector3(0, 0, 0);\n  Vector3 v2 = Vector3(10, 0, 0), w2 = Vector3(0, 0, 0);\n\n  // init values\n  Pose3 p1i(Rot3::Ypr(0.1, -0.1, -0.1), Point3(0.1, 0.1, -0.1));\n  Pose3 p2i(Rot3::Ypr(-0.1, 0.1, -0.1), Point3(1.1, -0.1, 0.1));\n  Vector3 v1i = Vector3(9.8, -0.1, -0.05), w1i = Vector3(0.1, -0.1, 0.1);\n  Vector3 v2i = Vector3(10.2, 0.03, -0.1), w2i = Vector3(-0.1, 0.1, 0.1);\n\n  // landmark and measurements\n  Point3 meas1 = pcam1.translation();\n  Point3 meas2 = pcam2.translation();\n  Point3 meas3 = pcam3.translation();\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Pose3>(Symbol('x', 1), p1, model_prior));\n  graph.add(PriorFactor<Pose3>(Symbol('x', 2), p2, model_prior));\n\n  graph.add(GaussianProcessPriorPose3VW(Symbol('x', 1), Symbol('v', 1), Symbol('w', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('w', 2), delta_t, Qc_model));\n  graph.add(GPSFactor(meas1, model_gps, Qc_model, Symbol('x', 1), Symbol('v', 1), Symbol('w', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('w', 2), delta_t, tau1));\n  graph.add(GPSFactor(meas2, model_gps, Qc_model, Symbol('x', 1), Symbol('v', 1), Symbol('w', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('w', 2), delta_t, tau2));\n  graph.add(GPSFactor(meas3, model_gps, Qc_model, Symbol('x', 1), Symbol('v', 1), Symbol('w', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('w', 2), delta_t, tau3));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), p1i);\n  init_values.insert(Symbol('v', 1), v1i);\n  init_values.insert(Symbol('w', 1), w1i);\n  init_values.insert(Symbol('x', 2), p2i);\n  init_values.insert(Symbol('v', 2), v2i);\n  init_values.insert(Symbol('w', 2), w2i);\n\n  GaussNewtonParams parameters;\n  parameters.setVerbosity(\"ERROR\");\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(p1, values.at<Pose3>(Symbol('x', 1)), 1e-6));\n  EXPECT(assert_equal(p2, values.at<Pose3>(Symbol('x', 2)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector3>(Symbol('v', 1)), 1e-6));\n  EXPECT(assert_equal(v2, values.at<Vector3>(Symbol('v', 2)), 1e-6));\n  EXPECT(assert_equal(w1, values.at<Vector3>(Symbol('w', 1)), 1e-6));\n  EXPECT(assert_equal(w2, values.at<Vector3>(Symbol('w', 2)), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/slam/tests/testGPInterpolatedProjectionFactorPose3.cpp",
    "content": "/**\n*  @file testGPInterpolatedProjectionFactorPose3.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/geometry/Cal3_S2.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/slam/GPInterpolatedProjectionFactorPose3.h>\n#include <gpslam/gp/GaussianProcessPriorPose3.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\ntypedef GPInterpolatedProjectionFactorPose3<Cal3_S2> ProjectionFactor;\n\n// error function wrapper for bind 10 params, by ignore default boost::none\ninline Vector errorWrapper(const ProjectionFactor& factor,\n    const Pose3& pose1, const Vector6& vel1,\n    const Pose3& pose2, const Vector6& vel2, const Point3& point) {\n  return factor.evaluateError(pose1, vel1, pose2, vel2, point);\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedProjectionFactorPose3, projection) {\n\n  noiseModel::Isotropic::shared_ptr model_cam =\n      noiseModel::Isotropic::Sigma(2, 0.1);\n  Matrix Qc = 0.001 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.04;\n  boost::shared_ptr<Cal3_S2> K1(new Cal3_S2());\n  boost::shared_ptr<Cal3_S2> K2(new Cal3_S2(50, 50, 0, 40, 30));\n  Pose3 body_T_sensor = Pose3(Rot3::Ypr(1.0, 0.4, 0.5), Point3(0.3, 0.6, -0.7));\n  Pose3 p1, p2;\n  Vector6 v1, v2;\n  Point3 land;\n  Point2 meas;\n  ProjectionFactor factor;\n  Vector expect, actual;\n  Matrix expectH1, expectH2, expectH3, expectH4, expectH5;\n  Matrix actualH1, actualH2, actualH3, actualH4, actualH5;\n\n  // test at origin, land is in front of z\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 0, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 0, 0, 0).finished();\n  land = Point3(0, 0, 10);\n  meas = Point2(0, 0);\n  factor = ProjectionFactor(meas, model_cam, Qc_model, 0, 0, 0, 0, 0, dt, tau, K1);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(2) << 0, 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // interpolat at origin: forward velocity\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(-0.04, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.06, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  land = Point3(0, 0, 10);\n  meas = Point2(0, 0);\n  factor = ProjectionFactor(meas, model_cam, Qc_model, 0, 0, 0, 0, 0, dt, tau, K1);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(2) << 0, 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // interpolat at origin: rotate\n  p1 = Pose3(Rot3::Ypr(-0.04, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0.06, 0, 0), Point3(0, 0, 0));\n  v1 = (Vector6() << 0, 0, 1, 0, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 1, 0, 0, 0).finished();\n  land = Point3(0, 0, 10);\n  meas = Point2(0, 0);\n  factor = ProjectionFactor(meas, model_cam, Qc_model, 0, 0, 0, 0, 0, dt, tau, K1);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(2) << 0, 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // forward velocity with random landmark: ground truth measurement by pinhole camera\n  // with body_P_sensor\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(1.5, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 15, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 15, 0, 0).finished();\n  // ground truth pose:\n  Pose3 ture_pose = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.6, 0, 0));\n  PinholeCamera<Cal3_S2> cam(ture_pose.compose(body_T_sensor), *K2);\n  land = Point3(3.4, 1.2, 10);\n  meas = cam.project(land);\n  factor = ProjectionFactor(meas, model_cam, Qc_model, 0, 0, 0, 0, 0, dt, tau, K2, body_T_sensor);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(2) << 0, 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-5));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedProjectionFactorPose3, optimization) {\n  /**\n   * A simple graph:\n   *\n   *   l1\n   *   |\n   *  proj1,2,3\n   *  /  \\\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   * |   |\n   * pv1 pv2\n   *\n   * p1 and p2 are constrained by GP prior and measurement, velcity is known.\n   * 3 measurements are given in different places\n   */\n\n\n  noiseModel::Isotropic::shared_ptr model_prior =\n      noiseModel::Isotropic::Sigma(6, 0.01);\n  noiseModel::Isotropic::shared_ptr model_cam =\n      noiseModel::Isotropic::Sigma(2, 0.1);\n  double delta_t = 0.1, tau1 = 0.02, tau2 = 0.06, tau3 = 0.09;\n  Matrix Qc = 0.01 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  // ground truth\n  Pose3 p1(Rot3(), Point3(0,0,0)), p2(Rot3(), Point3(1,0,0));\n  Pose3 pcam1(Rot3(), Point3(0.2,0,0)), pcam2(Rot3(), Point3(0.6,0,0)),\n      pcam3(Rot3(), Point3(0.9,0,0));\n  Vector6 v1 = (Vector6() << 0, 0, 0, 10, 0, 0).finished();\n  Vector6 v2 = (Vector6() << 0, 0, 0, 10, 0, 0).finished();\n\n  // init values\n  Pose3 p1i(Rot3::Ypr(0.1, 0.2, 0.4), Point3(0.2, 0.3, -0.2));\n  Pose3 p2i(Rot3::Ypr(-0.1, -0.2, -0.4), Point3(1.2, -0.3, 0.2));\n  Vector6 v1i = (Vector6() << -0.3, 0, 0, 0.7, 0, 0.2).finished();\n  Vector6 v2i = (Vector6() << 0, 0, 0.4, 1.2, 0, -0.1).finished();\n\n  // landmark and measurements\n  boost::shared_ptr<Cal3_S2> K(new Cal3_S2(50, 50, 0, 40, 30));\n  Point3 land = Point3(3.4, 1.2, 20);\n  Point3 landi = Point3(3.3, 1.3, 18);\n  PinholeCamera<Cal3_S2> cam1(pcam1, *K);\n  Point2 meas1 = cam1.project(land);\n  PinholeCamera<Cal3_S2> cam2(pcam2, *K);\n  Point2 meas2 = cam2.project(land);\n  PinholeCamera<Cal3_S2> cam3(pcam3, *K);\n  Point2 meas3 = cam3.project(land);\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Pose3>(Symbol('x', 1), p1, model_prior));\n  graph.add(PriorFactor<Pose3>(Symbol('x', 2), p2, model_prior));\n  //graph.add(PriorFactor<Vector6>(Symbol('v', 1), v1, model_prior));\n  //graph.add(PriorFactor<Vector6>(Symbol('v', 2), v2, model_prior));\n  graph.add(GaussianProcessPriorPose3(Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, Qc_model));\n  graph.add(ProjectionFactor(meas1, model_cam, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), delta_t, tau1, K));\n  graph.add(ProjectionFactor(meas2, model_cam, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), delta_t, tau2, K));\n  graph.add(ProjectionFactor(meas3, model_cam, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), delta_t, tau3, K));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), p1i);\n  init_values.insert(Symbol('v', 1), v1i);\n  init_values.insert(Symbol('x', 2), p2i);\n  init_values.insert(Symbol('v', 2), v2i);\n  init_values.insert(Symbol('l', 1), landi);\n\n  GaussNewtonParams parameters;\n  parameters.setVerbosity(\"ERROR\");\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(p1, values.at<Pose3>(Symbol('x', 1)), 1e-6));\n  EXPECT(assert_equal(p2, values.at<Pose3>(Symbol('x', 2)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector6>(Symbol('v', 1)), 1e-6));\n  EXPECT(assert_equal(v2, values.at<Vector6>(Symbol('v', 2)), 1e-6));\n  EXPECT(assert_equal(land, values.at<Point3>(Symbol('l', 1)), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/slam/tests/testGPInterpolatedRangeFactor2DLinear.cpp",
    "content": "/**\n*  @file testGPInterpolatedRangeFactor2DLinear.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/geometry/Pose2.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/slam/GPInterpolatedRangeFactor2DLinear.h>\n#include <gpslam/gp/GaussianProcessPriorLinear.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\ntypedef GPInterpolatedRangeFactor2DLinear RangeFactor;\n\n// error function wrapper for bind 10 params, by ignore default boost::none\ninline Vector errorWrapper(const RangeFactor& factor,\n    const Vector3& pose1, const Vector3& vel1,\n    const Vector3& pose2, const Vector3& vel2, const Point2& point) {\n  return factor.evaluateError(pose1, vel1, pose2, vel2, point);\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedRangeFactor2DLinear, range) {\n\n  noiseModel::Isotropic::shared_ptr model_range =\n      noiseModel::Isotropic::Sigma(1, 0.1);\n  Matrix Qc = 0.001 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.04;\n  Vector3 p1, p2;\n  Vector3 v1, v2;\n  Point2 land;\n  double meas;\n  RangeFactor factor;\n  Vector expect, actual;\n  Matrix expectH1, expectH2, expectH3, expectH4, expectH5;\n  Matrix actualH1, actualH2, actualH3, actualH4, actualH5;\n\n  // test at origin, land is in front of z\n  p1 = (Vector3() << 0, 0, 0).finished();\n  p2 = (Vector3() << 0, 0, 0).finished();\n  v1 = (Vector3() << 0, 0, 0).finished();\n  v2 = (Vector3() << 0, 0, 0).finished();\n  land = Point2(0, 10);\n  meas = 10;\n  factor = RangeFactor(meas, 0, 0, 0, 0, 0, model_range, Qc_model, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // interpolat at origin: forward velocity\n  p1 = (Vector3() << -0.04, 0, 0).finished();\n  p2 = (Vector3() << 0.06, 0, 0).finished();\n  v1 = (Vector3() << 1, 0, 0).finished();\n  v2 = (Vector3() << 1, 0, 0).finished();\n  land = Point2(0, 10);\n  meas = 10;\n  factor = RangeFactor(meas, 0, 0, 0, 0, 0, model_range, Qc_model, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // interpolat at origin: rotate\n  p1 = (Vector3() << 0, 0, -0.04).finished();\n  p2 = (Vector3() << 0, 0, 0.06).finished();\n  v1 = (Vector3() << 0, 0, 1).finished();\n  v2 = (Vector3() << 0, 0, 1).finished();\n  land = Point2(0, 10);\n  meas = 10;\n  factor = RangeFactor(meas, 0, 0, 0, 0, 0, model_range, Qc_model, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // interpolat at origin: rotate with non-zero rotation bias\n  p1 = (Vector3() << 0, 0, 10 * M_PI - 0.04).finished();\n  p2 = (Vector3() << 0, 0, 10 * M_PI + 0.06).finished();\n  v1 = (Vector3() << 0, 0, 1).finished();\n  v2 = (Vector3() << 0, 0, 1).finished();\n  land = Point2(0, 10);\n  meas = 10;\n  factor = RangeFactor(meas, 0, 0, 0, 0, 0, model_range, Qc_model, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // forward velocity with random landmark: ground truth measurement by pinhole camera\n  p1 = (Vector3() << 0, 0, 0).finished();\n  p2 = (Vector3() << 1.5, 0, 0).finished();\n  v1 = (Vector3() << 15, 0, 0).finished();\n  v2 = (Vector3() << 15, 0, 0).finished();\n  // ground truth pose:\n  Pose2 ture_pose = Pose2(0.6, 0, 0);\n  land = Point2(3.4, 1.2);\n  meas = ture_pose.range(land);\n  factor = RangeFactor(meas, 0, 0, 0, 0, 0, model_range, Qc_model, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n  // random stuff to test jacobians\n  p1 = (Vector3() << 5.34, 7.1, -4.32).finished();\n  p2 = (Vector3() << 1.5, -2.2, 3.0).finished();\n  v1 = (Vector3() << 15, 21.3, 32).finished();\n  v2 = (Vector3() << -15, 4.2, -30).finished();\n  // ground truth pose:\n  land = Point2(3.4, 1.2);\n  factor = RangeFactor(meas, 0, 0, 0, 0, 0, model_range, Qc_model, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedRangeFactor2DLinear, optimization) {\n  /**\n   * A simple graph:\n   *\n   *   l1 - pl1_loss\n   *   |\n   *  range1,2,3\n   *  /  \\\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   * |   |\n   * pv1 pv2\n   *\n   * p1 and p2 are constrained by GP prior and measurement, velcity is known.\n   * 3 measurements are given in different places (on a line)\n   * landmark need a prior since it's a diverge example\n   */\n\n  const double rotation_bias = 10 * M_PI;\n\n  noiseModel::Isotropic::shared_ptr model_prior =  noiseModel::Isotropic::Sigma(3, 0.01);\n  noiseModel::Isotropic::shared_ptr model_prior2_loss = noiseModel::Isotropic::Sigma(2, 0.1);\n  noiseModel::Isotropic::shared_ptr model_cam = noiseModel::Isotropic::Sigma(1, 0.1);\n  double delta_t = 0.5, tau1 = 0.05, tau2 = 0.25, tau3 = 0.45;\n  Matrix Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  // ground truth\n  Vector3 p1 = (Vector3() << 0,0, rotation_bias + 0).finished(),\n      p2 = (Vector3() << 5,0, rotation_bias + 0).finished();\n  Vector3 pcam1 = (Vector3() << 0.5,0,rotation_bias + 0).finished(),\n      pcam2 = (Vector3() << 2.5,0, rotation_bias + 0).finished(),\n      pcam3 = (Vector3() << 4.5,0, rotation_bias + 0).finished();\n  Vector3 v1 = (Vector3() << 10, 0, 0).finished();\n  Vector3 v2 = (Vector3() << 10, 0, 0).finished();\n\n  // init values\n  Vector3 p1i = (Vector3() << 0.1, 0.1, rotation_bias - 0.1).finished();\n  Vector3 p2i = (Vector3() << 5.1, -0.1, rotation_bias + 0.1).finished();\n  Vector3 v1i = (Vector3() << 9.8, 0, 0.2).finished();\n  Vector3 v2i = (Vector3() << 10.2, 0, -0.1).finished();\n\n  // landmark and measurements\n  Point2 land = Point2(2.4, 3.2);\n  Point2 landi = Point2(2.3, 3.1);\n  double meas1 = Pose2(pcam1(0), pcam1(1), pcam1(2)).range(land);\n  double meas2 = Pose2(pcam2(0), pcam2(1), pcam2(2)).range(land);\n  double meas3 = Pose2(pcam3(0), pcam3(1), pcam3(2)).range(land);\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Vector3>(Symbol('x', 1), p1, model_prior));\n  graph.add(PriorFactor<Vector3>(Symbol('x', 2), p2, model_prior));\n  graph.add(PriorFactor<Point2>(Symbol('l', 1), land, model_prior2_loss));\n  graph.add(PriorFactor<Vector3>(Symbol('v', 1), v1, model_prior));\n  graph.add(PriorFactor<Vector3>(Symbol('v', 2), v2, model_prior));\n\n  graph.add(GaussianProcessPriorLinear<3>(Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, Qc_model));\n\n  graph.add(RangeFactor(meas1, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), model_cam, Qc_model, delta_t, tau1));\n  graph.add(RangeFactor(meas2, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), model_cam, Qc_model, delta_t, tau2));\n  graph.add(RangeFactor(meas3, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), model_cam, Qc_model, delta_t, tau3));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), p1i);\n  init_values.insert(Symbol('v', 1), v1i);\n  init_values.insert(Symbol('x', 2), p2i);\n  init_values.insert(Symbol('v', 2), v2i);\n  init_values.insert(Symbol('l', 1), landi);\n\n  GaussNewtonParams parameters;\n  parameters.setVerbosity(\"ERROR\");\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-4);\n  EXPECT(assert_equal(p1, values.at<Vector3>(Symbol('x', 1)), 1e-4));\n  EXPECT(assert_equal(p2, values.at<Vector3>(Symbol('x', 2)), 1e-4));\n  EXPECT(assert_equal(v1, values.at<Vector3>(Symbol('v', 1)), 1e-4));\n  EXPECT(assert_equal(v2, values.at<Vector3>(Symbol('v', 2)), 1e-4));\n  EXPECT(assert_equal(land, values.at<Point2>(Symbol('l', 1)), 1e-4));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/slam/tests/testGPInterpolatedRangeFactorPose2.cpp",
    "content": "/**\n*  @file testGPInterpolatedRangeFactorPose2.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/geometry/Cal3_S2.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/slam/GPInterpolatedRangeFactorPose2.h>\n#include <gpslam/gp/GaussianProcessPriorPose2.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\ntypedef GPInterpolatedRangeFactorPose2 RangeFactor;\n\n// error function wrapper for bind 10 params, by ignore default boost::none\ninline Vector errorWrapper(const RangeFactor& factor,\n    const Pose2& pose1, const Vector3& vel1,\n    const Pose2& pose2, const Vector3& vel2, const Point2& point) {\n  return factor.evaluateError(pose1, vel1, pose2, vel2, point);\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedRangeFactorPose2, range) {\n\n  noiseModel::Isotropic::shared_ptr model_range =\n      noiseModel::Isotropic::Sigma(1, 0.1);\n  Matrix Qc = 0.001 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.04;\n  Pose2 p1, p2;\n  Vector3 v1, v2;\n  Point2 land;\n  double meas;\n  RangeFactor factor;\n  Vector expect, actual;\n  Matrix expectH1, expectH2, expectH3, expectH4, expectH5;\n  Matrix actualH1, actualH2, actualH3, actualH4, actualH5;\n\n  // test at origin, land is in front of z\n  p1 = Pose2(0, 0, 0);\n  p2 = Pose2(0, 0, 0);\n  v1 = (Vector3() << 0, 0, 0).finished();\n  v2 = (Vector3() << 0, 0, 0).finished();\n  land = Point2(0, 10);\n  meas = 10;\n  factor = RangeFactor(meas, model_range, Qc_model, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // interpolat at origin: forward velocity\n  p1 = Pose2(-0.04, 0, 0);\n  p2 = Pose2(0.06, 0, 0);\n  v1 = (Vector3() << 1, 0, 0).finished();\n  v2 = (Vector3() << 1, 0, 0).finished();\n  land = Point2(0, 10);\n  meas = 10;\n  factor = RangeFactor(meas, model_range, Qc_model, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // interpolat at origin: rotate\n  p1 = Pose2(0, 0, -0.04);\n  p2 = Pose2(0, 0, 0.06);\n  v1 = (Vector3() << 0, 0, 1).finished();\n  v2 = (Vector3() << 0, 0, 1).finished();\n  land = Point2(0, 10);\n  meas = 10;\n  factor = RangeFactor(meas, model_range, Qc_model, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // forward velocity with random landmark: ground truth measurement by pinhole camera\n  p1 = Pose2(0, 0, 0);\n  p2 = Pose2(1.5, 0, 0);\n  v1 = (Vector3() << 15, 0, 0).finished();\n  v2 = (Vector3() << 15, 0, 0).finished();\n  // ground truth pose:\n  Pose2 ture_pose = Pose2(0.6, 0, 0);\n  land = Point2(3.4, 1.2);\n  meas = ture_pose.range(land);\n  factor = RangeFactor(meas, model_range, Qc_model, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-4);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n  // random stuff to test jacobians\n  p1 = Pose2(5.34, 7.1, -4.32);\n  p2 = Pose2(1.5, -2.2, 3.0);\n  v1 = (Vector3() << 15, 21.3, 32).finished();\n  v2 = (Vector3() << -15, 4.2, -30).finished();\n  // ground truth pose:\n  land = Point2(3.4, 1.2);\n  factor = RangeFactor(meas, model_range, Qc_model, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedRangeFactorPose2, optimization) {\n  /**\n   * A simple graph:\n   *\n   *   l1 - pl1_loss\n   *   |\n   *  range1,2,3\n   *  /  \\\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   * |   |\n   * pv1 pv2\n   *\n   * p1 and p2 are constrained by GP prior and measurement, velcity is known.\n   * 3 measurements are given in different places (on a line)\n   * landmark need a prior since it's a diverge example\n   */\n\n  noiseModel::Isotropic::shared_ptr model_prior =  noiseModel::Isotropic::Sigma(3, 0.01);\n  noiseModel::Isotropic::shared_ptr model_prior2_loss = noiseModel::Isotropic::Sigma(2, 0.1);\n  noiseModel::Isotropic::shared_ptr model_cam = noiseModel::Isotropic::Sigma(1, 0.1);\n  double delta_t = 0.5, tau1 = 0.05, tau2 = 0.25, tau3 = 0.45;\n  Matrix Qc = 0.01 * Matrix::Identity(3,3);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  // ground truth\n  Pose2 p1(0,0,0), p2(5,0,0);\n  Pose2 pcam1(0.5,0,0), pcam2(2.5,0,0), pcam3(4.5,0,0);\n  Vector3 v1 = (Vector3() << 10, 0, 0).finished();\n  Vector3 v2 = (Vector3() << 10, 0, 0).finished();\n\n  // init values\n  Pose2 p1i(0.1, 0.1, -0.1);\n  Pose2 p2i(5.1, -0.1, 0.1);\n  Vector3 v1i = (Vector3() << 9.8, 0, 0.2).finished();\n  Vector3 v2i = (Vector3() << 10.2, 0, -0.1).finished();\n\n  // landmark and measurements\n  Point2 land = Point2(2.4, 3.2);\n  Point2 landi = Point2(2.3, 3.1);\n  double meas1 = pcam1.range(land);\n  double meas2 = pcam2.range(land);\n  double meas3 = pcam3.range(land);\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Pose2>(Symbol('x', 1), p1, model_prior));\n  graph.add(PriorFactor<Pose2>(Symbol('x', 2), p2, model_prior));\n  graph.add(PriorFactor<Point2>(Symbol('l', 1), land, model_prior2_loss));\n  graph.add(PriorFactor<Vector3>(Symbol('v', 1), v1, model_prior));\n  graph.add(PriorFactor<Vector3>(Symbol('v', 2), v2, model_prior));\n\n  graph.add(GaussianProcessPriorPose2(Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, Qc_model));\n\n  graph.add(RangeFactor(meas1, model_cam, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), delta_t, tau1));\n  graph.add(RangeFactor(meas2, model_cam, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), delta_t, tau2));\n  graph.add(RangeFactor(meas3, model_cam, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), delta_t, tau3));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), p1i);\n  init_values.insert(Symbol('v', 1), v1i);\n  init_values.insert(Symbol('x', 2), p2i);\n  init_values.insert(Symbol('v', 2), v2i);\n  init_values.insert(Symbol('l', 1), landi);\n\n  GaussNewtonParams parameters;\n  parameters.setVerbosity(\"ERROR\");\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-4);\n  EXPECT(assert_equal(p1, values.at<Pose2>(Symbol('x', 1)), 1e-4));\n  EXPECT(assert_equal(p2, values.at<Pose2>(Symbol('x', 2)), 1e-4));\n  EXPECT(assert_equal(v1, values.at<Vector3>(Symbol('v', 1)), 1e-4));\n  EXPECT(assert_equal(v2, values.at<Vector3>(Symbol('v', 2)), 1e-4));\n  EXPECT(assert_equal(land, values.at<Point2>(Symbol('l', 1)), 1e-4));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/slam/tests/testGPInterpolatedRangeFactorPose3.cpp",
    "content": "/**\n*  @file testGPInterpolatedRangeFactorPose3.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Matrix.h>\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/geometry/Cal3_S2.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n\n#include <gpslam/slam/GPInterpolatedRangeFactorPose3.h>\n#include <gpslam/gp/GaussianProcessPriorPose3.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\ntypedef GPInterpolatedRangeFactorPose3 RangeFactor;\n\n// error function wrapper for bind 10 params, by ignore default boost::none\ninline Vector errorWrapper(const RangeFactor& factor,\n    const Pose3& pose1, const Vector6& vel1,\n    const Pose3& pose2, const Vector6& vel2, const Point3& point) {\n  return factor.evaluateError(pose1, vel1, pose2, vel2, point);\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedRangeFactorPose3, range) {\n\n  noiseModel::Isotropic::shared_ptr model_range =\n      noiseModel::Isotropic::Sigma(1, 0.1);\n  Matrix Qc = 0.001 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n  double dt = 0.1, tau = 0.04;\n  Pose3 body_T_sensor = Pose3(Rot3::Ypr(1.0, 0.4, 0.5), Point3(0.3, 0.6, -0.7));\n  Pose3 p1, p2;\n  Vector6 v1, v2;\n  Point3 land;\n  double meas;\n  RangeFactor factor;\n  Vector expect, actual;\n  Matrix expectH1, expectH2, expectH3, expectH4, expectH5;\n  Matrix actualH1, actualH2, actualH3, actualH4, actualH5;\n\n  // test at origin, land is in front of z\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 0, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 0, 0, 0).finished();\n  land = Point3(0, 0, 10);\n  meas = 10;\n  factor = RangeFactor(meas, model_range, Qc_model, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-6);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-6);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-6);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // interpolat at origin: forward velocity\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(-0.04, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.06, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 1, 0, 0).finished();\n  land = Point3(0, 0, 10);\n  meas = 10;\n  factor = RangeFactor(meas, model_range, Qc_model, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // interpolat at origin: rotate\n  p1 = Pose3(Rot3::Ypr(-0.04, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0.06, 0, 0), Point3(0, 0, 0));\n  v1 = (Vector6() << 0, 0, 1, 0, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 1, 0, 0, 0).finished();\n  land = Point3(0, 0, 10);\n  meas = 10;\n  factor = RangeFactor(meas, model_range, Qc_model, 0, 0, 0, 0, 0, dt, tau);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n\n  // forward velocity with random landmark: ground truth measurement by pinhole camera\n  // with body_P_sensor\n  p1 = Pose3(Rot3::Ypr(0, 0, 0), Point3(0, 0, 0));\n  p2 = Pose3(Rot3::Ypr(0, 0, 0), Point3(1.5, 0, 0));\n  v1 = (Vector6() << 0, 0, 0, 15, 0, 0).finished();\n  v2 = (Vector6() << 0, 0, 0, 15, 0, 0).finished();\n  // ground truth pose:\n  Pose3 ture_pose = Pose3(Rot3::Ypr(0, 0, 0), Point3(0.6, 0, 0));\n  land = Point3(3.4, 1.2, 10);\n  meas = (ture_pose.compose(body_T_sensor)).range(land);\n  factor = RangeFactor(meas, model_range, Qc_model, 0, 0, 0, 0, 0, dt, tau, body_T_sensor);\n  actual = factor.evaluateError(p1, v1, p2, v2, land, actualH1, actualH2,\n      actualH3, actualH4, actualH5);\n  expect = ((Vector(1) << 0).finished());\n  expectH1 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, _1, v1, p2, v2, land)), p1, 1e-4);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, _1, p2, v2, land)), v1, 1e-4);\n  expectH3 = numericalDerivative11(boost::function<Vector(const Pose3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, _1, v2, land)), p2, 1e-4);\n  expectH4 = numericalDerivative11(boost::function<Vector(const Vector6&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, _1, land)), v2, 1e-4);\n  expectH5 = numericalDerivative11(boost::function<Vector(const Point3&)>(\n      boost::bind(&errorWrapper, factor, p1, v1, p2, v2, _1)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n  EXPECT(assert_equal(expectH3, actualH3, 1e-6));\n  //EXPECT(assert_equal(expectH4, actualH4, 1e-6));\n  EXPECT(assert_equal(expectH4, actualH4, 1e-5));\n  EXPECT(assert_equal(expectH5, actualH5, 1e-6));\n\n}\n\n/* ************************************************************************** */\nTEST(GPInterpolatedRangeFactorPose3, optimization) {\n  /**\n   * A simple graph:\n   *\n   *   l1 - pl1_loss\n   *   |\n   *  range1,2,3\n   *  /  \\\n   * x1   x2\n   *  \\  /\n   *   gp\n   *  /  \\\n   * v1  v2\n   * |   |\n   * pv1 pv2\n   *\n   * p1 and p2 are constrained by GP prior and measurement, velcity is known.\n   * 3 measurements are given in different places (on a line)\n   * landmark need a prior since it's a diverge example\n   */\n\n\n  noiseModel::Isotropic::shared_ptr model_prior =  noiseModel::Isotropic::Sigma(6, 0.01);\n  noiseModel::Isotropic::shared_ptr model_prior3_loss = noiseModel::Isotropic::Sigma(3, 0.1);\n  noiseModel::Isotropic::shared_ptr model_cam = noiseModel::Isotropic::Sigma(1, 0.1);\n  double delta_t = 0.1, tau1 = -0.1, tau2 = 0.05, tau3 = 0.2;\n  Matrix Qc = 0.01 * Matrix::Identity(6,6);\n  noiseModel::Gaussian::shared_ptr Qc_model = noiseModel::Gaussian::Covariance(Qc);\n\n  // ground truth\n  Pose3 p1(Rot3(), Point3(0,0,0)), p2(Rot3(), Point3(1,0,0));\n  Pose3 pcam1(Rot3(), Point3(-1,0,0)), pcam2(Rot3(), Point3(0.5,0,0)),\n      pcam3(Rot3(), Point3(2,0,0));\n  Vector6 v1 = (Vector6() << 0, 0, 0, 10, 0, 0).finished();\n  Vector6 v2 = (Vector6() << 0, 0, 0, 10, 0, 0).finished();\n\n  // init values\n  Pose3 p1i(Rot3::Ypr(0.1, 0.2, 0.4), Point3(0.2, 0.3, -0.2));\n  Pose3 p2i(Rot3::Ypr(-0.1, -0.2, -0.4), Point3(1.2, -0.3, 0.2));\n  Vector6 v1i = (Vector6() << -0.1, 0, 0, 0.8, 0, 0.2).finished();\n  Vector6 v2i = (Vector6() << 0, 0, 0.2, 1.2, 0, -0.1).finished();\n\n  // landmark and measurements\n  Point3 land = Point3(0.4, 1.2, 3);\n  Point3 landi = Point3(0.3, 1.1, 2.9);\n  double meas1 = pcam1.range(land);\n  double meas2 = pcam2.range(land);\n  double meas3 = pcam3.range(land);\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Pose3>(Symbol('x', 1), p1, model_prior));\n  graph.add(PriorFactor<Pose3>(Symbol('x', 2), p2, model_prior));\n  graph.add(PriorFactor<Point3>(Symbol('l', 1), land, model_prior3_loss));\n  graph.add(PriorFactor<Vector6>(Symbol('v', 1), v1, model_prior));\n  graph.add(PriorFactor<Vector6>(Symbol('v', 2), v2, model_prior));\n  graph.add(GaussianProcessPriorPose3(Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), delta_t, Qc_model));\n  graph.add(RangeFactor(meas1, model_cam, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), delta_t, tau1));\n  graph.add(RangeFactor(meas2, model_cam, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), delta_t, tau2));\n  graph.add(RangeFactor(meas3, model_cam, Qc_model, Symbol('x', 1), Symbol('v', 1),\n      Symbol('x', 2), Symbol('v', 2), Symbol('l', 1), delta_t, tau3));\n\n  Values init_values;\n  init_values.insert(Symbol('x', 1), p1i);\n  init_values.insert(Symbol('v', 1), v1i);\n  init_values.insert(Symbol('x', 2), p2i);\n  init_values.insert(Symbol('v', 2), v2i);\n  init_values.insert(Symbol('l', 1), landi);\n\n  GaussNewtonParams parameters;\n  parameters.setVerbosity(\"ERROR\");\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(p1, values.at<Pose3>(Symbol('x', 1)), 1e-6));\n  EXPECT(assert_equal(p2, values.at<Pose3>(Symbol('x', 2)), 1e-6));\n  EXPECT(assert_equal(v1, values.at<Vector6>(Symbol('v', 1)), 1e-6));\n  EXPECT(assert_equal(v2, values.at<Vector6>(Symbol('v', 2)), 1e-6));\n  EXPECT(assert_equal(land, values.at<Point3>(Symbol('l', 1)), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/slam/tests/testOdometryFactor2DLinear.cpp",
    "content": "/**\n*  @file testRangeFactor2DLinear.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n#include <gtsam/slam/BetweenFactor.h>\n\n#include <gpslam/slam/OdometryFactor2DLinear.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n/* ************************************************************************** */\nTEST(OdometryFactor2DLinear, Factor) {\n\n  noiseModel::Gaussian::shared_ptr model = noiseModel::Isotropic::Sigma(3, 1.0);\n  Key key_pose1 = Symbol('x', 1), key_pose2 = Symbol('x', 2);\n  Vector3 pose1, pose2, measured;\n  OdometryFactor2DLinear factor;\n  Matrix actualH1, actualH2;\n  Matrix expectH1, expectH2;\n  Vector actual, expect;\n\n  // origin: zero case (not differentiable)\n  pose1 = Vector3(0, 0, 0);\n  pose2 = Vector3(0, 0, 0);\n  measured = Vector3(0, 0, 0);\n  factor = OdometryFactor2DLinear(key_pose1, key_pose2, measured, model);\n  actual = factor.evaluateError(pose1, pose2);\n  expect = (Vector(3) << 0, 0, 0).finished();\n  EXPECT(assert_equal(expect, actual, 1e-6));\n\n  // case 1\n  pose1 = Vector3(0, 0, 0);\n  pose2 = Vector3(1, 0, 0);\n  measured = Vector3(1, 0, 0);\n  factor = OdometryFactor2DLinear(key_pose1, key_pose2, measured, model);\n  actual = factor.evaluateError(pose1, pose2, actualH1, actualH2);\n  expect = (Vector(3) << 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&OdometryFactor2DLinear::evaluateError, factor,\n          _1, pose2, boost::none, boost::none)), pose1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&OdometryFactor2DLinear::evaluateError, factor,\n          pose1, _1, boost::none, boost::none)), pose2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n\n\n  // case 2\n  pose1 = Vector3(42, 24, 1.570796326794897);\n  pose2 = Vector3(42, 25, 2.570796326794897);\n  measured = Vector3(1, 0, 1.0);\n  factor = OdometryFactor2DLinear(key_pose1, key_pose2, measured, model);\n  actual = factor.evaluateError(pose1, pose2, actualH1, actualH2);\n  expect = (Vector(3) << 0, 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&OdometryFactor2DLinear::evaluateError, factor,\n          _1, pose2, boost::none, boost::none)), pose1, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&OdometryFactor2DLinear::evaluateError, factor,\n          pose1, _1, boost::none, boost::none)), pose2, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/slam/tests/testRangeBearingFactor2DLinear.cpp",
    "content": "/**\n*  @file testRangeBearingFactor2DLinear.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n#include <gtsam/slam/BetweenFactor.h>\n\n#include <gpslam/slam/RangeBearingFactor2DLinear.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n/* ************************************************************************** */\nTEST(RangeBearingFactor2DLinear, Factor) {\n\n  noiseModel::Gaussian::shared_ptr model = noiseModel::Isotropic::Sigma(2, 1.0);\n  Key key_pose = Symbol('x', 1), key_lnd = Symbol('l', 1);\n  Vector3 pose;\n  Point2 land;\n  RangeBearingFactor2DLinear factor;\n  Matrix actualH1, actualH2;\n  Matrix expectH1, expectH2;\n  Vector actual, expect;\n\n  // case 1\n  pose = Vector3(3, 4, 0);\n  land = Point2(7, 7);\n  factor = RangeBearingFactor2DLinear(key_pose, key_lnd, 5.0, 0.643501108793284, model);\n  actual = factor.evaluateError(pose, land, actualH1, actualH2);\n  expect = (Vector(2) << 0, 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&RangeBearingFactor2DLinear::evaluateError, factor,\n          _1, land, boost::none, boost::none)), pose, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&RangeBearingFactor2DLinear::evaluateError, factor,\n          pose, _1, boost::none, boost::none)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n\n  // random case\n  pose = Vector3(13.1, -4.8, 1.5);\n  land = Point2(-5.4, 6.6);\n  factor = RangeBearingFactor2DLinear(key_pose, key_lnd, 13.1, 0.0, model);\n  actual = factor.evaluateError(pose, land, actualH1, actualH2);\n  expect = (Vector(2) << 1.089334716657378, 8.630393461693233).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&RangeBearingFactor2DLinear::evaluateError, factor,\n          _1, land, boost::none, boost::none)), pose, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&RangeBearingFactor2DLinear::evaluateError, factor,\n          pose, _1, boost::none, boost::none)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n}\n\n/* ************************************************************************** */\nTEST(RangeBearingFactor2DLinear, Optimization) {\n\n  /**\n   * A simple graph:\n   *\n   *     l\n   *  p /|\\\n   *  |/ | \\\n   *  x1-x2-x3\n   *\n   * p is pose prior factor to fix the poses, poses are connected by between factor\n   * calculated l correctly\n   */\n\n  noiseModel::Gaussian::shared_ptr meas_model = noiseModel::Isotropic::Sigma(2, 0.1);\n  noiseModel::Gaussian::shared_ptr prior_model = noiseModel::Isotropic::Sigma(3, 1.0);\n  noiseModel::Gaussian::shared_ptr between_model = noiseModel::Isotropic::Sigma(3, 0.1);\n  Key key_p1 = Symbol('x', 1), key_p2 = Symbol('x', 2), key_p3 = Symbol('x', 3);\n  Key key_lnd = Symbol('l', 1);\n\n  // ground truth\n  Vector3 p1 = Vector3(0, 0, 0);\n  Vector3 p2 = Vector3(1, 0, 0);\n  Vector3 p3 = Vector3(2, 1, 0);\n  Point2 lnd = Point2(0, 2);\n\n  // meas\n  double dist1 = 2.0, dist2 = 2.2360679775, dist3 = 2.2360679775;\n  Rot2 bear1(1.570796326794897), bear2(2.034443935795703), bear3(2.677945044588987);\n  Vector3 btw12 = Vector3(1, 0, 0), btw23 = Vector3(1, 1, 0);\n\n  // noisy init\n  Vector3 p1_init = Vector3(0.2, -0.5, 0.3);\n  Vector3 p2_init = Vector3(0.8, 0.2, 0.1);\n  Vector3 p3_init = Vector3(2.4, 1.3, -0.4);\n  Point2 lnd_init = Point2(0.1, 2.2);\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Vector3>(key_p1, p1, prior_model));\n  graph.add(BetweenFactor<Vector3>(key_p1, key_p2, btw12, between_model));\n  graph.add(BetweenFactor<Vector3>(key_p2, key_p3, btw23, between_model));\n  graph.add(RangeBearingFactor2DLinear(key_p1, key_lnd, dist1, bear1, meas_model));\n  graph.add(RangeBearingFactor2DLinear(key_p2, key_lnd, dist2, bear2, meas_model));\n  graph.add(RangeBearingFactor2DLinear(key_p3, key_lnd, dist3, bear3, meas_model));\n\n  Values init_values;\n  init_values.insert(key_p1, p1_init);\n  init_values.insert(key_p2, p2_init);\n  init_values.insert(key_p3, p3_init);\n  init_values.insert(key_lnd, lnd_init);\n\n  GaussNewtonParams parameters;\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(p1, values.at<Vector3>(key_p1), 1e-6));\n  EXPECT(assert_equal(p2, values.at<Vector3>(key_p2), 1e-6));\n  EXPECT(assert_equal(p3, values.at<Vector3>(key_p3), 1e-6));\n  EXPECT(assert_equal(lnd, values.at<Point2>(key_lnd), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/slam/tests/testRangeFactor2DLinear.cpp",
    "content": "/**\n*  @file testRangeFactor2DLinear.cpp\n*  @author Jing Dong\n**/\n\n#include <CppUnitLite/TestHarness.h>\n\n#include <gtsam/base/Testable.h>\n#include <gtsam/base/numericalDerivative.h>\n#include <gtsam/inference/Symbol.h>\n#include <gtsam/nonlinear/NonlinearFactorGraph.h>\n#include <gtsam/nonlinear/GaussNewtonOptimizer.h>\n#include <gtsam/nonlinear/Values.h>\n#include <gtsam/slam/PriorFactor.h>\n#include <gtsam/slam/BetweenFactor.h>\n\n#include <gpslam/slam/RangeFactor2DLinear.h>\n\n#include <iostream>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\n\n\n/* ************************************************************************** */\nTEST(RangeFactor2DLinear, Factor) {\n\n  noiseModel::Gaussian::shared_ptr model = noiseModel::Isotropic::Sigma(1, 1.0);\n  Key key_pose = Symbol('x', 1), key_lnd = Symbol('l', 1);\n  Vector3 pose;\n  Point2 land;\n  RangeFactor2DLinear factor;\n  Matrix actualH1, actualH2;\n  Matrix expectH1, expectH2;\n  Vector actual, expect;\n\n  // origin: zero case (not differentiable)\n  pose = Vector3(0, 0, 0);\n  land = Point2(0, 0);\n  factor = RangeFactor2DLinear(key_pose, key_lnd, 0.0, model);\n  actual = factor.evaluateError(pose, land);\n  expect = (Vector(1) << 0).finished();\n  EXPECT(assert_equal(expect, actual, 1e-6));\n\n  // case 1\n  pose = Vector3(3, 4, 5);\n  land = Point2(7, 7);\n  factor = RangeFactor2DLinear(key_pose, key_lnd, 5.0, model);\n  actual = factor.evaluateError(pose, land, actualH1, actualH2);\n  expect = (Vector(1) << 0).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&RangeFactor2DLinear::evaluateError, factor,\n          _1, land, boost::none, boost::none)), pose, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&RangeFactor2DLinear::evaluateError, factor,\n          pose, _1, boost::none, boost::none)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n\n  // random case\n  pose = Vector3(13.1, -4.8, 1.5);\n  land = Point2(-5.4, 6.6);\n  factor = RangeFactor2DLinear(key_pose, key_lnd, 13.1, model);\n  actual = factor.evaluateError(pose, land, actualH1, actualH2);\n  expect = (Vector(1) << 8.630393461693233).finished();\n  expectH1 = numericalDerivative11(boost::function<Vector(const Vector3&)>(\n      boost::bind(&RangeFactor2DLinear::evaluateError, factor,\n          _1, land, boost::none, boost::none)), pose, 1e-6);\n  expectH2 = numericalDerivative11(boost::function<Vector(const Point2&)>(\n      boost::bind(&RangeFactor2DLinear::evaluateError, factor,\n          pose, _1, boost::none, boost::none)), land, 1e-6);\n  EXPECT(assert_equal(expect, actual, 1e-6));\n  EXPECT(assert_equal(expectH1, actualH1, 1e-6));\n  EXPECT(assert_equal(expectH2, actualH2, 1e-6));\n}\n\n/* ************************************************************************** */\nTEST(RangeFactor2DLinear, Optimization) {\n\n  /**\n   * A simple graph:\n   *\n   *     l\n   *  p /|\\\n   *  |/ | \\\n   *  x1-x2-x3\n   *\n   * p is pose prior factor to fix the poses, poses are connected by between factor\n   * calculated l correctly\n   */\n\n  noiseModel::Gaussian::shared_ptr meas_model = noiseModel::Isotropic::Sigma(1, 0.1);\n  noiseModel::Gaussian::shared_ptr prior_model = noiseModel::Isotropic::Sigma(3, 1.0);\n  noiseModel::Gaussian::shared_ptr between_model = noiseModel::Isotropic::Sigma(3, 0.1);\n  Key key_p1 = Symbol('x', 1), key_p2 = Symbol('x', 2), key_p3 = Symbol('x', 3);\n  Key key_lnd = Symbol('l', 1);\n\n  // ground truth\n  Vector3 p1 = Vector3(0, 0, 0);\n  Vector3 p2 = Vector3(1, 0, 0);\n  Vector3 p3 = Vector3(2, 1, 0);\n  Point2 lnd = Point2(0, 2);\n\n  // meas\n  double dist1 = 2.0, dist2 = 2.2360679775, dist3 = 2.2360679775;\n  Vector3 btw12 = Vector3(1, 0, 0), btw23 = Vector3(1, 1, 0);\n\n  // noisy init\n  Vector3 p1_init = Vector3(0.2, -0.5, 0.3);\n  Vector3 p2_init = Vector3(0.8, 0.2, 0.1);\n  Vector3 p3_init = Vector3(2.4, 1.3, -0.4);\n  Point2 lnd_init = Point2(0.1, 2.2);\n\n  NonlinearFactorGraph graph;\n  graph.add(PriorFactor<Vector3>(key_p1, p1, prior_model));\n  graph.add(BetweenFactor<Vector3>(key_p1, key_p2, btw12, between_model));\n  graph.add(BetweenFactor<Vector3>(key_p2, key_p3, btw23, between_model));\n  graph.add(RangeFactor2DLinear(key_p1, key_lnd, dist1, meas_model));\n  graph.add(RangeFactor2DLinear(key_p2, key_lnd, dist2, meas_model));\n  graph.add(RangeFactor2DLinear(key_p3, key_lnd, dist3, meas_model));\n\n  Values init_values;\n  init_values.insert(key_p1, p1_init);\n  init_values.insert(key_p2, p2_init);\n  init_values.insert(key_p3, p3_init);\n  init_values.insert(key_lnd, lnd_init);\n\n  GaussNewtonParams parameters;\n  GaussNewtonOptimizer optimizer(graph, init_values, parameters);\n  optimizer.optimize();\n  Values values = optimizer.values();\n\n  EXPECT_DOUBLES_EQUAL(0, graph.error(values), 1e-6);\n  EXPECT(assert_equal(p1, values.at<Vector3>(key_p1), 1e-6));\n  EXPECT(assert_equal(p2, values.at<Vector3>(key_p2), 1e-6));\n  EXPECT(assert_equal(p3, values.at<Vector3>(key_p3), 1e-6));\n  EXPECT(assert_equal(lnd, values.at<Point2>(key_lnd), 1e-6));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam/slam/tests/testSerializationSLAM.cpp",
    "content": "/**\n*  @file testSerialization.cpp\n*  @brief test serialization of all factors\n*  @author Jing Dong\n**/\n\n#include <gpslam/slam/GPInterpolatedGPSFactorPose3.h>\n#include <gpslam/slam/GPInterpolatedGPSFactorPose3VW.h>\n#include <gpslam/slam/GPInterpolatedProjectionFactorPose3.h>\n#include <gpslam/slam/GPInterpolatedRangeFactorPose3.h>\n\n#include <gpslam/slam/OdometryFactor2DLinear.h>\n#include <gpslam/slam/RangeBearingFactor2DLinear.h>\n#include <gpslam/slam/RangeFactor2DLinear.h>\n#include <gpslam/slam/RangeBearingFactor2DLinear.h>\n\n#include <gtsam/base/serializationTestHelpers.h>\n#include <CppUnitLite/TestHarness.h>\n\nusing namespace std;\nusing namespace gtsam;\nusing namespace gpslam;\nusing namespace gtsam::serializationTestHelpers;\n\n\nBOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, \"gtsam_noiseModel_Constrained\");\nBOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, \"gtsam_noiseModel_Diagonal\");\nBOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, \"gtsam_noiseModel_Gaussian\");\nBOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, \"gtsam_noiseModel_Unit\");\nBOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, \"gtsam_noiseModel_Isotropic\");\nBOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, \"gtsam_SharedNoiseModel\");\nBOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, \"gtsam_SharedDiagonal\");\n\n/* ************************************************************************** */\n// data\nstatic SharedNoiseModel unit1 = noiseModel::Unit::Create(1);\nstatic SharedNoiseModel unit2 = noiseModel::Unit::Create(2);\nstatic SharedNoiseModel unit3 = noiseModel::Unit::Create(3);\nstatic SharedNoiseModel Qcmodel_6 = noiseModel::Isotropic::Sigma(6, 0.1);\nstatic Cal3_S2::shared_ptr K(new Cal3_S2());\n\n// factors\nstatic GPInterpolatedGPSFactorPose3 gp_gps_pose3(Point3(0.3, 0.6, 0.9), unit2, Qcmodel_6, 1, 2, 3, 4, 0.1, 0.04);\nstatic GPInterpolatedGPSFactorPose3VW gp_gps_pose3vw(Point3(0.3, 0.6, 0.9), unit2,\n    Qcmodel_6, 1, 2, 3, 4, 5, 6, 0.1, 0.04);\nstatic GPInterpolatedProjectionFactorPose3<Cal3_S2> gp_proj(Point2(10, 20), unit2,\n    Qcmodel_6, 1, 2, 3, 4, 5, 0.1, 0.04, K);\nstatic GPInterpolatedRangeFactorPose3 gp_range(10.0, unit1, Qcmodel_6, 1, 2, 3, 4, 5, 0.1, 0.04);\n\nstatic OdometryFactor2DLinear odom_linear2(1, 2, Vector3(0.1, 0.2, 3.0), unit3);\nstatic RangeFactor2DLinear range_linear2(1, 2, 10.0, unit1);\nstatic RangeBearingFactor2DLinear rangebearing_linear2(1, 2, 0.1, 10.0, unit2);\n\n/* ************************************************************************** */\nTEST(SerializationSLAM, text) {\n  EXPECT(equalsObj(gp_gps_pose3));\n  EXPECT(equalsObj(gp_gps_pose3vw));\n  EXPECT(equalsObj(gp_proj));\n  EXPECT(equalsObj(gp_range));\n\n  EXPECT(equalsObj(odom_linear2));\n  EXPECT(equalsObj(range_linear2));\n  EXPECT(equalsObj(rangebearing_linear2));\n}\n\n/* ************************************************************************** */\nTEST(SerializationSLAM, xml) {\n  EXPECT(equalsXML(gp_gps_pose3));\n  EXPECT(equalsXML(gp_gps_pose3vw));\n  EXPECT(equalsXML(gp_proj));\n  EXPECT(equalsXML(gp_range));\n\n  EXPECT(equalsXML(odom_linear2));\n  EXPECT(equalsXML(range_linear2));\n  EXPECT(equalsXML(rangebearing_linear2));\n}\n\n/* ************************************************************************** */\nTEST(SerializationSLAM, binary) {\n  EXPECT(equalsBinary(gp_gps_pose3));\n  EXPECT(equalsBinary(gp_gps_pose3vw));\n  EXPECT(equalsBinary(gp_proj));\n  EXPECT(equalsBinary(gp_range));\n\n  EXPECT(equalsBinary(odom_linear2));\n  EXPECT(equalsBinary(range_linear2));\n  EXPECT(equalsBinary(rangebearing_linear2));\n}\n\n/* ************************************************************************** */\n/* main function */\nint main() {\n  TestResult tr;\n  return TestRegistry::runAllTests(tr);\n}\n"
  },
  {
    "path": "gpslam.h",
    "content": "// GP-SLAM wrapper\n\n// delearation\nclass gtsam::Vector6;\nclass gtsam::Vector3;\nclass gtsam::Rot2;\nclass gtsam::Point2;\nclass gtsam::Pose2;\nclass gtsam::Rot3;\nclass gtsam::Point3;\nclass gtsam::Pose3;\nclass gtsam::Unit3;\nclass gtsam::Cal3_S2;\n\nclass gtsam::GaussianFactorGraph;\nclass gtsam::Values;\n\nvirtual class gtsam::noiseModel::Base;\nvirtual class gtsam::NonlinearFactor;\nvirtual class gtsam::NonlinearFactorGraph;\nvirtual class gtsam::NoiseModelFactor;\n\n\nnamespace gpslam {\n\n////////////////////////////////////////////////////////////////////////////////\n// Lie classes\n////////////////////////////////////////////////////////////////////////////////\n\n// prior factor\n#include <gpslam/gp/GaussianProcessPriorPose3.h>\nvirtual class GaussianProcessPriorPose3 : gtsam::NoiseModelFactor {\n  GaussianProcessPriorPose3(size_t key1, size_t key2, size_t key3, size_t key4,\n      double delta, const gtsam::noiseModel::Base* Qc_model);\n};\n\n#include <gpslam/gp/GaussianProcessPriorPose3VW.h>\nvirtual class GaussianProcessPriorPose3VW : gtsam::NoiseModelFactor {\n  GaussianProcessPriorPose3VW(size_t key1, size_t key2, size_t key3, size_t key4,\n      size_t key5, size_t key6, double delta, const gtsam::noiseModel::Base* Qc_model);\n};\n\n#include <gpslam/gp/GaussianProcessPriorPose2.h>\nvirtual class GaussianProcessPriorPose2 : gtsam::NoiseModelFactor {\n  GaussianProcessPriorPose2(size_t key1, size_t key2, size_t key3, size_t key4,\n      double delta, const gtsam::noiseModel::Base* Qc_model);\n};\n\n#include <gpslam/gp/GaussianProcessPriorRot3.h>\nvirtual class GaussianProcessPriorRot3 : gtsam::NoiseModelFactor {\n  GaussianProcessPriorRot3(size_t key1, size_t key2, size_t key3, size_t key4,\n      double delta, const gtsam::noiseModel::Base* Qc_model);\n};\n\n// util class for all interpolated measurements\n#include <gpslam/gp/GaussianProcessInterpolatorPose3.h>\nclass GaussianProcessInterpolatorPose3 {\n  GaussianProcessInterpolatorPose3(const gtsam::noiseModel::Base* Qc_model,\n      double delta_t, double tau);\n  gtsam::Pose3 interpolatePose(const gtsam::Pose3& pose1, Vector vel1,\n        const gtsam::Pose3& pose2, Vector vel2) const;\n};\n\n#include <gpslam/gp/GaussianProcessInterpolatorPose3VW.h>\nclass GaussianProcessInterpolatorPose3VW {\n  GaussianProcessInterpolatorPose3VW(const gtsam::noiseModel::Base* Qc_model,\n      double delta_t, double tau);\n  gtsam::Pose3 interpolatePose(const gtsam::Pose3& pose1, Vector vel1, Vector w1,\n        const gtsam::Pose3& pose2, Vector vel2, Vector w2) const;\n};\n\n#include <gpslam/gp/GaussianProcessInterpolatorPose2.h>\nclass GaussianProcessInterpolatorPose2 {\n  GaussianProcessInterpolatorPose2(const gtsam::noiseModel::Base* Qc_model,\n      double delta_t, double tau);\n  gtsam::Pose2 interpolatePose(const gtsam::Pose2& pose1, Vector vel1,\n        const gtsam::Pose2& pose2, Vector vel2) const;\n};\n\n#include <gpslam/gp/GaussianProcessInterpolatorRot3.h>\nclass GaussianProcessInterpolatorRot3 {\n  GaussianProcessInterpolatorRot3(const gtsam::noiseModel::Base* Qc_model,\n      double delta_t, double tau);\n  gtsam::Rot3 interpolatePose(const gtsam::Rot3& pose1, Vector vel1,\n        const gtsam::Rot3& pose2, Vector vel2) const;\n};\n\n\n\n// projection factor\n#include <gpslam/slam/GPInterpolatedProjectionFactorPose3.h>\ntemplate <CALIBRATION>\nvirtual class GPInterpolatedProjectionFactorPose3 : gtsam::NoiseModelFactor {\n  GPInterpolatedProjectionFactorPose3(const gtsam::Point2& measured,\n      const gtsam::noiseModel::Base* cam_model, const gtsam::noiseModel::Base* Qc_model,\n      size_t pose1Key, size_t vel1Key, size_t pose2Key, size_t vel2Key,\n      size_t pointKey, double delta_t, double tau, const CALIBRATION* k);\n  GPInterpolatedProjectionFactorPose3(const gtsam::Point2& measured,\n      const gtsam::noiseModel::Base* cam_model, const gtsam::noiseModel::Base* Qc_model,\n      size_t pose1Key, size_t vel1Key, size_t pose2Key, size_t vel2Key,\n      size_t pointKey, double delta_t, double tau, const CALIBRATION* k,\n      const gtsam::Pose3& body_P_sensor);\n  GPInterpolatedProjectionFactorPose3(const gtsam::Point2& measured,\n      const gtsam::noiseModel::Base* cam_model, const gtsam::noiseModel::Base* Qc_model,\n      size_t pose1Key, size_t vel1Key, size_t pose2Key, size_t vel2Key,\n      size_t pointKey, double delta_t, double tau, const CALIBRATION* k,\n      const gtsam::Pose3& body_P_sensor, bool throwCheirality, bool verboseCheirality);\n};\n\ntypedef gpslam::GPInterpolatedProjectionFactorPose3<gtsam::Cal3_S2> GPInterpolatedProjectionFactorPose3Cal3_S2;\n\n\n\n// range factor\n#include <gpslam/slam/RangeFactorPose2.h>\nvirtual class RangeFactorPose2 : gtsam::NoiseModelFactor {\n  RangeFactorPose2(size_t posekey, size_t landkey,\n      double measured, const gtsam::noiseModel::Base* model);\n};\n\n#include <gpslam/slam/GPInterpolatedRangeFactorPose2.h>\nvirtual class GPInterpolatedRangeFactorPose2 : gtsam::NoiseModelFactor {\n  GPInterpolatedRangeFactorPose2(double measured,\n      const gtsam::noiseModel::Base* meas_model, const gtsam::noiseModel::Base* Qc_model,\n      size_t pose1Key, size_t vel1Key, size_t pose2Key, size_t vel2Key,\n      size_t pointKey, double delta_t, double tau);\n  GPInterpolatedRangeFactorPose2(double measured,\n      const gtsam::noiseModel::Base* meas_model, const gtsam::noiseModel::Base* Qc_model,\n      size_t pose1Key, size_t vel1Key, size_t pose2Key, size_t vel2Key,\n      size_t pointKey, double delta_t, double tau, const gtsam::Pose2& body_P_sensor);\n};\n\n\n#include <gpslam/slam/GPInterpolatedRangeFactorPose3.h>\nvirtual class GPInterpolatedRangeFactorPose3 : gtsam::NoiseModelFactor {\n  GPInterpolatedRangeFactorPose3(double measured,\n      const gtsam::noiseModel::Base* meas_model, const gtsam::noiseModel::Base* Qc_model,\n      size_t pose1Key, size_t vel1Key, size_t pose2Key, size_t vel2Key,\n      size_t pointKey, double delta_t, double tau);\n  GPInterpolatedRangeFactorPose3(double measured,\n      const gtsam::noiseModel::Base* meas_model, const gtsam::noiseModel::Base* Qc_model,\n      size_t pose1Key, size_t vel1Key, size_t pose2Key, size_t vel2Key,\n      size_t pointKey, double delta_t, double tau, const gtsam::Pose3& body_P_sensor);\n};\n\n// attitude factor\n#include <gpslam/slam/GPInterpolatedAttitudeFactorRot3.h>\nvirtual class GPInterpolatedAttitudeFactorRot3 : gtsam::NoiseModelFactor {\n  GPInterpolatedAttitudeFactorRot3(\n      size_t poseKey1, size_t velKey1, size_t poseKey2, size_t velKey2,\n      double delta_t, double tau, const gtsam::noiseModel::Base* Qc_model,\n      const gtsam::noiseModel::Base* meas_model, const gtsam::Unit3& nZ, const gtsam::Unit3& bRef);\n  GPInterpolatedAttitudeFactorRot3(\n      size_t poseKey1, size_t velKey1, size_t poseKey2, size_t velKey2,\n      double delta_t, double tau, const gtsam::noiseModel::Base* Qc_model,\n      const gtsam::noiseModel::Base* meas_model, const gtsam::Unit3& nZ);\n};\n\n\n/// get body-centric velocity from two poses and delta_t\nVector getBodyCentricVb(const gtsam::Pose3& pose1, const gtsam::Pose3& pose2,\n    double delta_t);\nVector getBodyCentricVs(const gtsam::Pose3& pose1, const gtsam::Pose3& pose2,\n    double delta_t);\n\n\n\n////////////////////////////////////////////////////////////////////////////////\n// Linear classes\n////////////////////////////////////////////////////////////////////////////////\n\n\n// prior factor\n#include <gpslam/gp/GaussianProcessPriorLinear.h>\n\n// template DOF list\ntemplate <DOF = {2,3}>\nvirtual class GaussianProcessPriorLinear : gtsam::NoiseModelFactor {\n  GaussianProcessPriorLinear(size_t key1, size_t key2, size_t key3, size_t key4,\n      double delta, const gtsam::noiseModel::Base* Qc_model);\n};\n\n\n// util class for all interpolated measurements\n#include <gpslam/gp/GaussianProcessInterpolatorLinear.h>\n\n// template DOF list\ntemplate <DOF = {2,3}>\nclass GaussianProcessInterpolatorLinear {\n  GaussianProcessInterpolatorLinear(const gtsam::noiseModel::Base* Qc_model,\n      double delta_t, double tau);\n  Vector interpolatePose(Vector pose1, Vector vel1, Vector pose2, Vector vel2) const;\n  Vector interpolateVelocity(Vector pose1, Vector vel1, Vector pose2, Vector vel2) const;\n};\n\n\n// odometry factor\n#include <gpslam/slam/OdometryFactor2DLinear.h>\nvirtual class OdometryFactor2DLinear : gtsam::NoiseModelFactor {\n  OdometryFactor2DLinear(size_t pose1Key, size_t pose2Key, Vector odomMeasured,\n      const gtsam::noiseModel::Base* model);\n};\n\n\n// range factor\n#include <gpslam/slam/RangeFactor2DLinear.h>\nvirtual class RangeFactor2DLinear : gtsam::NoiseModelFactor {\n  RangeFactor2DLinear(size_t posekey, size_t landkey,\n      double measured, const gtsam::noiseModel::Base* model);\n};\n\n#include <gpslam/slam/GPInterpolatedRangeFactor2DLinear.h>\nvirtual class GPInterpolatedRangeFactor2DLinear : gtsam::NoiseModelFactor {\n  GPInterpolatedRangeFactor2DLinear(double measured,\n      size_t pose1Key, size_t vel1Key, size_t pose2Key, size_t vel2Key, size_t pointKey,\n      const gtsam::noiseModel::Base* meas_model, const gtsam::noiseModel::Base* Qc_model,\n      double delta_t, double tau);\n};\n\n\n// bearing range factor\n#include <gpslam/slam/RangeBearingFactor2DLinear.h>\nvirtual class RangeBearingFactor2DLinear : gtsam::NoiseModelFactor {\n  RangeBearingFactor2DLinear(size_t posekey, size_t landkey, double measured,\n      const gtsam::Rot2& bearing, const gtsam::noiseModel::Base* model);\n};\n\n}\n\n"
  },
  {
    "path": "matlab/AHRSexample.m",
    "content": "% AHRS example without using GP\n% Jing 02.08.2016\n\nclear\nclose all\nimport gtsam.*\nimport gpslam.*\n\n%% settings\nuseGyro = true;\nuseAcc = true;\nuseGaussNewton = false;\nuseGyroInit = true;\n\ndatasetMaxTime = 90.0;\noptimizeStopRelErr = 1e-6;\nmaxIteration = 100;\n\n% noisemodel\nbiasPriorModel = noiseModel.Diagonal.Sigmas([1 1 1]' * 1e-2);\nbiasBetweenModel = noiseModel.Diagonal.Sigmas([1 1 1]' * 1e-4);\ngyroNoiseModel = noiseModel.Diagonal.Sigmas([1 1 1]' * 1e-4);\ngyroNoiseModelMat = [1 0 0; 0 1 0; 0 0 1] * 1e-3;\naccNoiseModel = noiseModel.Diagonal.Sigmas([1 1]' * 0.1);\nfirstRotPriorModel = noiseModel.Diagonal.Sigmas([1 1 1]' * 0.1);\n\n%% load data\n\ndataset_path = '/home/jing/data/imu/mocap_022304/parsed_matlab/';\natt_mocap = true;\n\n% IMU format: seq, time(sec), gyro_x/y/z, acc_x/y/z\nimu_filename = 'RAW_IMU_DATA_matlab.txt';\n% ATT format: seq, time(sec), ori_x/y/z/w\n% att_filename = 'ATTITUDE_IMU_DATA_matlab.txt';\natt_filename = 'MOCAP_POSE_DATA_matlab.txt';\n\nIMU = load(strcat(dataset_path, imu_filename));\nATT = load(strcat(dataset_path, att_filename));\n\n% mocap reformat\nif att_mocap\n    ATT = ATT(:, [1:2, 6:9]);\nend\n\nnr_imu = size(IMU, 1);\nnr_att = size(ATT, 1);\n\n% convert ATT to ypr format\nload_att_ypr = false;\n\n% ATT_YPR format: y/p/r\nATT_YPR = zeros(nr_att, 3);\natt_ypr_filename = 'ATT_YPR_matlab.mat';\n\nif load_att_ypr\n    load(strcat(dataset_path, att_ypr_filename), 'ATT_YPR');\nelse\n    for i=1:nr_att\n        % wxyz in gtsam Rot3 constructor\n        rot3 = Rot3.Quaternion(ATT(i, 6), ATT(i, 3), ATT(i, 4), ATT(i, 5));\n        ATT_YPR(i,:) = rot3.ypr();\n    end\n    save(strcat(dataset_path, att_ypr_filename), 'ATT_YPR');\nend\n\n% % mocap reformat\n% if att_mocap\n%     ATT_YPR(:,2:3) = [ATT_YPR(:,3), -ATT_YPR(:,2)];\n% end\n\n%% plot gound truth\nfigure(2)\n\n% pitch\nsubplot(3,1,1)\nhold on\nplot(ATT(:, 2), ATT_YPR(:,2), 'g-');\naxis([0 datasetMaxTime -pi pi])\nhold off\ntitle('Pitch')\n\n% roll\nsubplot(3,1,2)\nhold on\nplot(ATT(:, 2), ATT_YPR(:,3), 'g-');\naxis([0 datasetMaxTime -pi pi])\nhold off\ntitle('Roll')\n\n% yaw\nsubplot(3,1,3)\nhold on\nplot(ATT(:, 2), ATT_YPR(:,1), 'g-');\naxis([0 datasetMaxTime -pi pi])\nhold off\ntitle('Yaw')\n\n\n%% build factor graph using gyro and acc\n\ngraph = NonlinearFactorGraph;\ngyro_graph = NonlinearFactorGraph;\ninit_values = Values;\n\nmeas_time = 0;\nvar_idx = 1;\nwhile meas_time < datasetMaxTime & var_idx <= nr_imu\n    \n    meas_time = IMU(var_idx, 2);\n    fprintf('Time: %d\\n', meas_time)\n    \n    % first bias: add prior\n    if var_idx == 1\n        graph.add(PriorFactorRot3(symbol('x', 1), Rot3, firstRotPriorModel));\n        insertVectorPriorFactor3(graph, symbol('b', 1), zeros(3,1), biasPriorModel);\n        \n        gyro_graph.add(PriorFactorRot3(symbol('x', 1), Rot3, firstRotPriorModel));\n        insertVectorPriorFactor3(gyro_graph, symbol('b', 1), zeros(3,1), biasPriorModel);\n    else\n        % gyro factors\n        biasHat = zeros(3,1);\n        delta_t = IMU(var_idx, 2) - IMU(var_idx-1, 2);\n        pim = PreintegratedAhrsMeasurements(biasHat, gyroNoiseModelMat);\n        pim.integrateMeasurement(IMU(var_idx, 3:5)', delta_t);\n        zcoriolis = zeros(3,1);\n\n        gyro_graph.add(AHRSFactor(symbol('x', var_idx - 1), symbol('x', var_idx), ...\n            symbol('b', var_idx - 1), pim, zcoriolis));\n        \n        if useGyro\n            graph.add(AHRSFactor(symbol('x', var_idx - 1), symbol('x', var_idx), ...\n                symbol('b', var_idx - 1), pim, zcoriolis));\n        end\n        \n        % bias factors\n        insertVectorBetweenFactor3(graph, symbol('b', var_idx - 1), symbol('b', var_idx), ...\n            zeros(3,1), biasBetweenModel);\n        insertVectorBetweenFactor3(gyro_graph, symbol('b', var_idx - 1), symbol('b', var_idx), ...\n            zeros(3,1), biasBetweenModel);\n    end\n    \n    % acc factors\n    if useAcc\n        % TODO: what's the correct acc input format?\n        graph.add(Rot3AttitudeFactor(symbol('x', var_idx), ...\n            Unit3(Point3(0, 0, 1)), accNoiseModel, ...\n            Unit3(Point3(IMU(var_idx, 6), IMU(var_idx, 7), IMU(var_idx, 8)))));\n    end\n    \n    % next iter\n    var_idx = var_idx + 1;\nend\nnr_opt = var_idx - 1;\n\n\n%% init values\n\n% init zero rotation values\nfor i=1:nr_opt\n    init_values.insert(symbol('x', i), Rot3);\n    init_values.insert(symbol('b', i), zeros(3,1));\nend\n\nif useGyroInit\n    % optimize gyro only graph\n    fprintf('Optimizing Gyro only graph ... \\n\\n');\n    if useGaussNewton\n        params = GaussNewtonParams;\n        optimizer = GaussNewtonOptimizer(gyro_graph, init_values, params);\n    else\n        params = LevenbergMarquardtParams;\n        optimizer = LevenbergMarquardtOptimizer(gyro_graph, init_values, params);\n    end\n    gyro_only_results = optimizer.optimize();\n    \n    for i=1:nr_opt\n        init_values.update(symbol('x', i), gyro_only_results.atRot3(symbol('x', i)));\n    end\nend\n\n\n%% optimize!\nif useGaussNewton\n    params = GaussNewtonParams;\n    optimizer = GaussNewtonOptimizer(graph, init_values, params);\nelse\n    params = LevenbergMarquardtParams;\n    optimizer = LevenbergMarquardtOptimizer(graph, init_values, params);\nend\n\n% optimize \nfprintf('init error: %d\\n', optimizer.error());\n\niter_time = [];\nopt_last_err = 1e20;\niter_count = 0;\ntic\nwhile (opt_last_err - optimizer.error())/opt_last_err > optimizeStopRelErr ...\n        && iter_count < maxIteration\n    opt_last_err = optimizer.error();\n    optimizer.iterate();\n    iter_count = iter_count + 1;\n    fprintf('iter %d: new error: %d\\n', iter_count, optimizer.error());\nend\nfprintf('Total Optimization Time: %d\\n', toc)\nresults = optimizer.values;\n\n\n%% prepare results\nOPT = zeros(nr_opt, 3);\nGYRO = zeros(nr_opt, 3);\nBIAS = zeros(nr_opt, 3);\n\nfor i=1:nr_opt\n    rot3 = results.atRot3(symbol('x', i));\n    OPT(i,:) = [rot3.yaw, rot3.pitch, rot3.roll];\n    \n    BIAS(i,:) = [results.atVector(symbol('b', i))'];\n    \n    if useGyroInit\n        rot3 = gyro_only_results.atRot3(symbol('x', i));\n        GYRO(i,:) = [rot3.yaw, rot3.pitch, rot3.roll];\n    end\nend\n\n\n%% plot\nfigure\n\n% pitch\nsubplot(3,1,1)\nhold on\nplot(ATT(:, 2), ATT_YPR(:,2), 'g-');\nif useGyroInit\n    plot(IMU(1:nr_opt, 2), GYRO(:,2), 'r-.');\nend\nplot(IMU(1:nr_opt, 2), OPT(:,2), 'b-');\naxis([0 datasetMaxTime -pi pi])\nhold off\ntitle('Pitch')\n\n% roll\nsubplot(3,1,2)\nhold on\nplot(ATT(:, 2), ATT_YPR(:,3), 'g-');\nif useGyroInit\n    plot(IMU(1:nr_opt, 2), GYRO(:,3), 'r-.');\nend\nplot(IMU(1:nr_opt, 2), OPT(:,3), 'b-');\naxis([0 datasetMaxTime -pi pi])\nhold off\ntitle('Roll')\n\n% bias\nsubplot(3,1,3)\nhold on\nplot(IMU(1:nr_opt, 2), BIAS(:,1), 'r-');\nplot(IMU(1:nr_opt, 2), BIAS(:,2), 'g-');\nplot(IMU(1:nr_opt, 2), BIAS(:,3), 'b-');\naxis([0 datasetMaxTime -1 1])\nhold off\ntitle('Bias')\n\n\n\n\n"
  },
  {
    "path": "matlab/GPAHRSexample.m",
    "content": "% AHRS example with GP, fuse asynchronous accelerometer and gyroscope data\n% @author Jing Dong \n% @date 02.15.2016\n\nclear\nclose all\nimport gtsam.*\nimport gpslam.*\n\n\n%% settings        \nuseGyro = true;         % use gyroscope information\nuseAcc = true;          % use accelerometer information\nuseGaussNewton = false; % use GN or LM solver\n\ndatasetMaxTime = 50.0;  % maximum dataset process time\noptimizeStopRelErr = 1e-6;  % relative error threshold to stop optimization \nmaxIteration = 100;     % max iteration to stop optimization \n\n% GP settings\nQcModel = noiseModel.Diagonal.Sigmas([1 1 1]' * 100);\n\n% noisemodel\nbiasPriorModel = noiseModel.Diagonal.Sigmas([1 1 1]' * 1e-2);\nbiasBetweenModel = noiseModel.Diagonal.Sigmas([1 1 1]' * 1e-4);\ngyroNoiseModel = noiseModel.Diagonal.Sigmas([1 1 1]' * 1e-4);\ngyroNoiseModelMat = [1 0 0; 0 1 0; 0 0 1] * 1e-3;\naccNoiseModel = noiseModel.Diagonal.Sigmas([1 1]' * 0.1);\nfirstRotPriorModel = noiseModel.Diagonal.Sigmas([1 1 1]' * 0.1);\n\n\n%% load data\n\n% Collected dataset has synchronous acc/gyro data.\n% To create an asynchronous dataset, we skip some measurements in different\n% frequency. Here we setup the data rate you want for acc/gyro data.\n% Time unit is second\ngyro_dt = 0.005;\nacc_dt = 0.02;\n\ndataset_path = 'data/';\n\n% IMU format: seq, time(sec), gyro_x/y/z, acc_x/y/z\nimu_filename = 'RAW_IMU_DATA_matlab.txt';\n% ATT format: seq, time(sec), ori_x/y/z/w\natt_filename = 'MOCAP_POSE_DATA_matlab.txt';\n\nIMU = load(strcat(dataset_path, imu_filename));\nMOCAP = load(strcat(dataset_path, att_filename));\n\n% get attitute data from motion captured poses\nATT = MOCAP(:, [1:2, 6:9]);\n\nnr_imu = size(IMU, 1);\nnr_att = size(ATT, 1);\n\n% ATT_YPR format yaw/pitch/roll : y/p/r\nATT_YPR = zeros(nr_att, 3);\nfor i=1:nr_att\n    % wxyz in gtsam Rot3 constructor\n    rot3 = Rot3.Quaternion(ATT(i, 6), ATT(i, 3), ATT(i, 4), ATT(i, 5));\n    ATT_YPR(i,:) = rot3.ypr();\nend\n\nbiasHat = zeros(3,1);       % bias prior: zero\nzcoriolis = zeros(3,1);     % coriolis force: ignore here\n\n\n%% build factor graph using gyro and acc\ngraph = NonlinearFactorGraph;\ngyro_graph = NonlinearFactorGraph;\n\nmeas_time = 0;\nlast_gyro_meas_time = 0;\nlast_acc_meas_time = 0;\nadd_rot_state = false;\n\n% cached acc factor information, since they can only be added when state is\n% determined by gyro\ncached_acc_add_idx = [];\nnr_acc = 0;\n\nvar_idx = 1;\ncached_state_meas_idx = [];\nmeas_idx = 1;\n\nfprintf('building factor graph ...\\n')\nwhile meas_time < datasetMaxTime & meas_idx <= nr_imu\n    \n    meas_time = IMU(meas_idx, 2);\n    \n    if (floor(meas_time) > floor(last_gyro_meas_time))\n        fprintf('Read dataset time: %ds ...\\n', floor(meas_time))\n    end\n    \n    if meas_idx > 1\n        delta_t = IMU(meas_idx, 2) - IMU(meas_idx-1, 2);\n    end\n    \n    \n    % acc factors, based on time interval with last\n    if useAcc & meas_time - last_acc_meas_time >= acc_dt\n        cached_acc_add_idx = [cached_acc_add_idx, meas_idx];\n        % next iter\n        last_acc_meas_time = meas_time;\n        nr_acc = nr_acc + 1;\n    end\n    \n    \n    % process Gyro measurements and decide system states time stamps \n    \n    % add states: start, end, and time stamp meet interval\n    if var_idx == 1 | meas_idx == nr_imu | meas_time - last_gyro_meas_time >= gyro_dt\n        \n        % first state: bias add prior\n        if var_idx == 1\n            graph.add(PriorFactorRot3(symbol('x', 1), Rot3.Ypr(ATT_YPR(1,1), ...\n                ATT_YPR(1,2), ATT_YPR(1,3)), firstRotPriorModel));\n            graph.add(PriorFactorVector(symbol('b', 1), zeros(3,1), biasPriorModel));\n            \n            gyro_graph.add(PriorFactorRot3(symbol('x', 1), Rot3.Ypr(ATT_YPR(1,1), ...\n                ATT_YPR(1,2), ATT_YPR(1,3)), firstRotPriorModel));\n            gyro_graph.add(PriorFactorVector(symbol('b', 1), zeros(3,1), biasPriorModel));\n            \n        % check gyro rate: if dt > gyro_dt then add new state\n        else\n            dt = meas_time - last_gyro_meas_time;       % for GP\n            \n            % integerate gyro for last step\n            pim.integrateMeasurement(IMU(meas_idx, 3:5)', delta_t);\n            \n            % gyro factors\n            gyro_graph.add(AHRSFactor(symbol('x', var_idx - 1), symbol('x', var_idx), ...\n                symbol('b', var_idx - 1), pim, zcoriolis));\n            \n            if useGyro\n                graph.add(AHRSFactor(symbol('x', var_idx - 1), symbol('x', var_idx), ...\n                    symbol('b', var_idx - 1), pim, zcoriolis));\n            end\n            \n            % bias factors\n            graph.add(BetweenFactorVector(symbol('b', var_idx - 1), symbol('b', var_idx), ...\n                zeros(3,1), biasBetweenModel));\n            gyro_graph.add(BetweenFactorVector(symbol('b', var_idx - 1), symbol('b', var_idx), ...\n                zeros(3,1), biasBetweenModel));\n            \n            % GP prior\n            graph.add(GaussianProcessPriorRot3(...\n                symbol('x', var_idx -1), symbol('v', var_idx -1), ...\n                symbol('x', var_idx), symbol('v', var_idx), ...\n                dt, QcModel));\n            \n            % add cached acc factor\n            for i=1:numel(cached_acc_add_idx)\n                \n                acc_idx = cached_acc_add_idx(i);\n                \n                % check whether interpolated factor\n                if acc_idx == meas_idx\n                    % non-inter\n                    % TODO: what's the correct acc input format?\n                    graph.add(Rot3AttitudeFactor(symbol('x', var_idx), ...\n                        Unit3(Point3(0, 0, 1)), accNoiseModel, ...\n                        Unit3(Point3(IMU(meas_idx, 6), IMU(meas_idx, 7), IMU(meas_idx, 8)))));\n                else\n                    % inter\n                    tau = IMU(acc_idx, 2) - last_gyro_meas_time;\n                    % TODO: what's the correct acc input format?\n                    graph.add(GPInterpolatedAttitudeFactorRot3(...\n                        symbol('x', var_idx -1), symbol('v', var_idx -1), ...\n                        symbol('x', var_idx), symbol('v', var_idx), ...\n                        dt, tau, QcModel, accNoiseModel, Unit3(Point3(0, 0, 1)), ...\n                        Unit3(Point3(IMU(meas_idx, 6), IMU(meas_idx, 7), IMU(meas_idx, 8)))));\n                end\n            end\n            cached_acc_add_idx = [];        % clear cache\n        end\n        \n        % prepare pre-integerated measurements\n        pim = PreintegratedAhrsMeasurements(biasHat, gyroNoiseModelMat);\n        \n        % next iter: add state\n        last_gyro_meas_time = meas_time;\n        cached_state_meas_idx = [cached_state_meas_idx, meas_idx];\n        var_idx = var_idx + 1;\n        add_rot_state = true;\n        \n    % not added as new state, just do pre-integeration\n    else\n        % just do integeration\n        pim.integrateMeasurement(IMU(meas_idx, 3:5)', delta_t);\n        \n        % next iter: not add state\n        add_rot_state = false;\n    end\n    \n    % meas next iter\n    meas_idx = meas_idx + 1;\n    \n    % actual dataset length used\n    actual_time = meas_time;\nend\n\nnr_opt = var_idx - 1;\n\nfprintf('\\nNumber of Gyroscope measurements used: %d\\n', nr_opt)\nfprintf('Number of Accelerometer measurements used: %d\\n', nr_acc)\n\nfprintf('\\nActual Gyroscope data frequency: %fHz\\n', nr_opt/actual_time)\nfprintf('Actual Accelerometer data frequency: %fHz\\n', nr_acc/actual_time)\n\n\n%% init values\ninit_values = Values;\n\n% init zero rotation values\nfor i=1:nr_opt\n    init_values.insert(symbol('x', i), Rot3);\n    init_values.insert(symbol('b', i), zeros(3,1));\nend\n\n% optimize gyro-only graph, update the initial values by gyro-only values\nfprintf('\\nOptimizing Gyro only graph (for initialization) ... \\n\\n');\nif useGaussNewton\n    params = GaussNewtonParams;\n    optimizer = GaussNewtonOptimizer(gyro_graph, init_values, params);\nelse\n    params = LevenbergMarquardtParams;\n    optimizer = LevenbergMarquardtOptimizer(gyro_graph, init_values, params);\nend\ngyro_only_results = optimizer.optimize();\n\nfor i=1:nr_opt\n    init_values.update(symbol('x', i), gyro_only_results.atRot3(symbol('x', i)));\nend\n\n% velocity for GP\nfor i=1:nr_opt\n    init_values.insert(symbol('v', i), zeros(3,1));\nend\n\n\n%% optimize!\nif useGaussNewton\n    params = GaussNewtonParams;\n    optimizer = GaussNewtonOptimizer(graph, init_values, params);\nelse\n    params = LevenbergMarquardtParams;\n    optimizer = LevenbergMarquardtOptimizer(graph, init_values, params);\nend\n\n% optimize \nfprintf('init error: %d\\n', optimizer.error());\n\niter_time = [];\nopt_last_err = 1e20;\niter_count = 0;\ntic\nwhile (opt_last_err - optimizer.error())/opt_last_err > optimizeStopRelErr ...\n        && iter_count < maxIteration\n    opt_last_err = optimizer.error();\n    optimizer.iterate();\n    iter_count = iter_count + 1;\n    fprintf('iter %d: new error: %d\\n', iter_count, optimizer.error());\nend\nfprintf('Total Optimization Time: %f\\n', toc)\nresults = optimizer.values;\n\n\n%% prepare results\nOPT = zeros(nr_opt, 3);\nGYRO = zeros(nr_opt, 3);\nBIAS = zeros(nr_opt, 3);\n\nfor i=1:nr_opt\n    rot3 = results.atRot3(symbol('x', i));\n    OPT(i,:) = [rot3.yaw, rot3.pitch, rot3.roll];\n    \n    BIAS(i,:) = [results.atVector(symbol('b', i))'];\n    \n    rot3 = gyro_only_results.atRot3(symbol('x', i));\n    GYRO(i,:) = [rot3.yaw, rot3.pitch, rot3.roll];\nend\n\n\n%% plot\n\n% pitch\nh = figure(1);\nsubplot(3,1,1)\nhold on\nplot(ATT(:, 2), ATT_YPR(:,2), '-', 'Color', [0, 0.8, 0]);\nplot(IMU(cached_state_meas_idx, 2), GYRO(:,2), 'r-.');\nplot(IMU(cached_state_meas_idx, 2), OPT(:,2), 'b-');\naxis([0 datasetMaxTime -pi pi])\nhold off\n% marks\ntitle('Pitch')\nylabel('Rad')\nxlabel('t (s)')\nbox on\nlegend('Ground truth', 'Gyro-only', 'Estimated', 'Location', 'northwest')\n\n\n% roll\nsubplot(3,1,2);\nhold on\nplot(ATT(:, 2), ATT_YPR(:,3), '-', 'Color', [0, 0.8, 0]);\nplot(IMU(cached_state_meas_idx, 2), GYRO(:,3), 'r-.');\nplot(IMU(cached_state_meas_idx, 2), OPT(:,3), 'b-');\naxis([0 datasetMaxTime -pi pi])\nhold off\n% marks\ntitle('Roll')\nylabel('Rad')\nxlabel('t (s)')\nbox on\nlegend('Ground truth', 'Gyro-only', 'Estimated', 'Location', 'northwest')\n\n\n% bias\nsubplot(3,1,3)\nhold on\nplot(IMU(cached_state_meas_idx, 2), BIAS(:,1), 'r-');\nplot(IMU(cached_state_meas_idx, 2), BIAS(:,2), 'g-');\nplot(IMU(cached_state_meas_idx, 2), BIAS(:,3), 'b-');\naxis([0 datasetMaxTime -1e-2 1e-2])\nhold off\n% marks\nbox on\ntitle('Bias')\nxlabel('t (s)')\nlegend('Pitch', 'Roll', 'Yaw', 'Location', 'northwest')\n\n\n\n\n"
  },
  {
    "path": "matlab/PlazaPose2.m",
    "content": "% 2D SLAM example using Range + Odometry data, Plaza datasets\n% dataset format: http://www.frc.ri.cmu.edu/projects/emergencyresponse/RangeData/log.html\n% @author Jing Dong\n% @date 02.05.2016\n\nclear\nclose all\nimport gtsam.*\nimport gpslam.*\n\n\n%% read datasets\ndatafile = 'data/Plaza2.mat';\nload(datafile);\n\nnr_pose = size(GT, 1);      % total number of poses\nnr_land = size(TL, 1);      % total number of landmarks\nnr_range = size(TD, 1);\nland_idx = TL(:,1);         % landmark indices\n\n% get range measurments bias fixed by linear fitting, and remove outliers\n% range_trans is linear fitting coefficient\n% range_outlier_mask is 0-1 mask of whether measurement is outlier\n[range_trans, range_outlier_mask] = range_measure_fit(GT, TL, TD);\n\n\n%% settings\nuseLinearPose2 = false;         % use linear [x y \\theta] or SE(2) system states\naddOdometry = true;             % use odometry information\n\ninitGroundTruth = false;        % use ground truth do initialization\naddFirstPosePrior = true;       % add pose prior to first pose (fix position of whole system)\naddFirstVelZeroPrior = false;   % add velocity prior to first velocity\naddLandmarkPrior = true;        % add (loss) prior to landmarks to fix scale and position of whole system\n\nuseGaussNewton = false;         % use GN or LM\noptimizeStopRelErr = 1e-6;      % relative error thresh hold to stop the optimization\n\n% GP settings\nQcModel = noiseModel.Diagonal.Sigmas([1 1 1]' * 1e-1);\n\n% noise models\nfirstPriorModel = noiseModel.Diagonal.Sigmas([1 1 pi]' * 1);\nodomNoiseModel = noiseModel.Diagonal.Sigmas([1 1 pi]' * 1e-3);\nrangeNoiseModel = noiseModel.Diagonal.Sigmas(0.5);\nlandPriorNoiseModel = noiseModel.Diagonal.Sigmas([1 1]' * 1);\n\n\n%% initial factor graph\n\ngraph = NonlinearFactorGraph;\ninit_values = Values;\n\n% initial landmarks\nfor i=1:nr_land\n    land_point = Point2(TL(i,2), TL(i,3));\n    \n    % init landmark values as ground truth\n    init_values.insert(symbol('l', land_idx(i)), land_point);\n    \n    % prior\n    if addLandmarkPrior\n        graph.add(PriorFactorPoint2(symbol('l', land_idx(i)), land_point, ...\n            landPriorNoiseModel));\n    end\nend\n\n% accumulated odometry poses\nDRp_pose2 = zeros(nr_pose, 3);\nDRp_pose2(1,:) = [GT(1, 2), GT(1, 3), GT(1, 4)+init_heading_offset];\n\nlast_pose = Pose2(GT(1, 2), GT(1, 3), GT(1, 4)+init_heading_offset);\nlast_vec = [GT(1, 2), GT(1, 3), GT(1, 4)+init_heading_offset]';\n\n% first pose and velocity prior\nif addFirstPosePrior\n    if useLinearPose2\n        graph.add(PriorFactorVector(symbol('x', 1), last_vec, firstPriorModel));\n    else\n        graph.add(PriorFactorPose2(symbol('x', 1), last_pose, firstPriorModel));\n    end\nend\nif addFirstVelZeroPrior\n    graph.add(PriorFactorVector(symbol('v', 1), zeros(3,1), firstPriorModel));\nend\n\nadded_range_meas_idx = 1;       % range measurement idx should be added next\n\nfprintf('building factor graph ...\\n');\nfor pose_idx = 1:nr_pose\n    \n    if mod(pose_idx, 100) == 0\n        fprintf('read pose idx %d of %d ...\\n', pose_idx, nr_pose);\n    end\n    \n    curr_time = GT(pose_idx, 1);\n    \n    if pose_idx > 1\n        last_time = GT(pose_idx-1, 1);\n        delta_t = curr_time - last_time;\n        \n        %% odometry & GP prior\n        % get odom measurement pose\n        odom_pose = Pose2(DR(pose_idx-1, 2), 0.0, DR(pose_idx-1, 3));\n        new_pose = last_pose.compose(odom_pose);\n        % odom vector\n        odom_vec_meas = [DR(pose_idx-1, 2), 0.0, DR(pose_idx-1, 3)]';\n        odom_vec = [new_pose.x() - last_pose.x(), new_pose.y() - last_pose.y(), ...\n            odom_pose.theta()]';\n        new_vec = last_vec + odom_vec;\n        \n        % accumulate odom poses\n        if useLinearPose2\n            DRp_pose2(pose_idx,:) = new_vec';\n        else\n            DRp_pose2(pose_idx,:) = [new_pose.x(), new_pose.y(), new_pose.theta()];\n        end\n        \n        % add odometry factor\n        if addOdometry\n            if useLinearPose2\n                graph.add(OdometryFactor2DLinear(symbol('x', pose_idx-1), symbol('x', pose_idx), ...\n                    odom_vec_meas, odomNoiseModel));\n            else\n                graph.add(BetweenFactorPose2(symbol('x', pose_idx-1), symbol('x', pose_idx), ...\n                    odom_pose, odomNoiseModel));\n            end\n        end\n        \n        % add GP prior factor\n        if useLinearPose2\n            graph.add(GaussianProcessPriorLinear3(symbol('x', pose_idx-1), ...\n                symbol('v', pose_idx-1), symbol('x', pose_idx), symbol('v', pose_idx), ...\n                delta_t, QcModel));\n        else\n            graph.add(GaussianProcessPriorPose2(symbol('x', pose_idx-1), ...\n                symbol('v', pose_idx-1), symbol('x', pose_idx), symbol('v', pose_idx), ...\n                delta_t, QcModel));\n        end\n  \n        % for next iter\n        last_pose = new_pose;\n        last_vec = new_vec;\n         \n        \n        %% add range measurements\n        while added_range_meas_idx <= nr_range & TD(added_range_meas_idx, 1) <= curr_time\n            \n            % check outlier mask, remove outliers\n            if ~range_outlier_mask(added_range_meas_idx)\n                \n                % get meas info\n                tau = TD(added_range_meas_idx, 1) - last_time;\n               \n                % range bias fix\n                meas_range = range_trans(1) * TD(added_range_meas_idx, 4) + range_trans(2);\n                meas_land_idx = TD(added_range_meas_idx, 3);\n\n%                 fprintf('range %d from pose %d to land %d, tau = %d, delta_t = %d \\n', ...\n%                     added_range_meas_idx, pose_idx, meas_land_idx, tau, delta_t);\n\n                % add interpolate range factor\n                if useLinearPose2\n                    graph.add(GPInterpolatedRangeFactor2DLinear(meas_range, ...\n                        symbol('x', pose_idx-1), symbol('v', pose_idx-1), ...\n                        symbol('x', pose_idx), symbol('v', pose_idx), ...\n                        symbol('l', meas_land_idx), rangeNoiseModel, QcModel, ...\n                        delta_t, tau));\n                else\n                    graph.add(GPInterpolatedRangeFactorPose2(meas_range, ...\n                        rangeNoiseModel, QcModel, symbol('x', pose_idx-1), ...\n                        symbol('v', pose_idx-1), symbol('x', pose_idx), symbol('v', pose_idx), ...\n                        symbol('l', meas_land_idx), delta_t, tau));\n                end\n            end\n            \n            added_range_meas_idx = added_range_meas_idx + 1;\n        end\n        \n    end\n\n    %% init values\n    if useLinearPose2\n        % if not use ground truth, just use last pose to initialize\n        if initGroundTruth\n            init_pose = [GT(pose_idx, 2), GT(pose_idx, 3), GT(pose_idx, 4)+init_heading_offset]';\n        else\n            init_pose = last_vec;\n        end\n        init_values.insert(symbol('x', pose_idx), init_pose);\n        \n    else\n        if initGroundTruth\n            init_pose = Pose2(GT(pose_idx, 2), GT(pose_idx, 3), GT(pose_idx, 4)+init_heading_offset);\n        else\n            init_pose = last_pose;\n        end\n        init_values.insert(symbol('x', pose_idx), init_pose);\n    end\n    \n    init_vel = zeros(3,1);\n    init_values.insert(symbol('v', pose_idx), init_vel);\n    \nend\n\n\n%% optimize!\nif useGaussNewton\n    params = GaussNewtonParams;\n    optimizer = GaussNewtonOptimizer(graph, init_values, params);\nelse\n    params = LevenbergMarquardtParams;\n    optimizer = LevenbergMarquardtOptimizer(graph, init_values, params);\nend\n\n% optimize \nfprintf('init error: %d\\n', optimizer.error());\n\niter_time = [];\nopt_last_err = 1e20;\n% tic\nwhile (opt_last_err - optimizer.error())/opt_last_err > optimizeStopRelErr\n    opt_last_err = optimizer.error();\n    tic\n    optimizer.iterate();\n    iter_time = [iter_time, toc];\n    fprintf('new error: %d\\n', optimizer.error());\nend\n% fprintf('Total Optimization Time: %d\\n', toc)\nresults = optimizer.values;\n\n% average time\nfprintf('Average Optimization Iteration Time: %d\\n', mean(iter_time))\n\n\n%% evaluate error\n\n% extract results to matrix\nOPT = zeros(nr_pose, 3);\nOPT_LAND = zeros(nr_land, 2);\nfor i=1:nr_pose\n    if useLinearPose2\n        OPT(i, :) = results.atVector(symbol('x', i))';\n    else\n        opt_pose2 = results.atPose2(symbol('x', i));\n        OPT(i, :) = [opt_pose2.x() opt_pose2.y(), opt_pose2.theta()];\n    end\nend\nfor i=1:nr_land\n    opt_land = results.atPoint2(symbol('l', land_idx(i)));\n    OPT_LAND(i, :) = [opt_land.x() opt_land.y()];\nend\n\n% position err\npos_err = OPT(:,1:2) - GT(:,2:3);\npos_err_sqrt = sqrt(pos_err(:,1).^2 + pos_err(:,2).^2);\nfprintf('Average Position Error: %d\\n', mean(pos_err_sqrt))\n\n% rotation err\nrot_err = OPT(:,3) - (GT(:,4)+init_heading_offset);\nfor i=1:nr_pose\n    while rot_err(i) < -pi\n        rot_err(i) = rot_err(i) + 2*pi;\n    end\n    while rot_err(i) > pi\n        rot_err(i) = rot_err(i) - 2*pi;\n    end\nend\nfprintf('Average Rotation Error: %d\\n', mean(abs(rot_err)) * 180 / pi)\n\n% land err err\nland_err = OPT_LAND(:,1:2) - TL(:,2:3);\nland_err_sqrt = sqrt(land_err(:,1).^2 + land_err(:,2).^2);\nfprintf('Average Landmark Error: %d\\n', mean(land_err_sqrt))\n\n\n%% plot results\n\n% plot results\nh = figure(1);\nhold on\naxis equal\n\n% plot traj\nplot(DRp(:,2), DRp(:,3), '-.', 'Color',[1 0 0])\n\nplot(GT(:,2), GT(:,3), '-', 'Color',[0 0.7 0])\nplot(OPT(:,1), OPT(:,2), '-', 'Color',[0 0 1])\n\n% plot land\nplot(TL(:,2), TL(:,3), '*', 'Color',[0 0.7 0], 'MarkerSize', 8, 'Linewidth', 1.5)\nplot(OPT_LAND(:,1), OPT_LAND(:,2), '+', 'Color',[0 0 1], 'MarkerSize', 8, 'Linewidth', 1.5)\n\n% marks\nax = gca;\nax.XTick = [-100:20:100];\nax.YTick = [-100:20:100];\n% box on\n\nlegend('Dead Reckoned Path', 'Ground Truth Trajectory', 'Estimated Trajectory', ...\n    'Ground Truth Landmark', 'Estimated Landmark')\nxlabel('X (m)')\nylabel('Y (m)')\nhold off\n\n"
  },
  {
    "path": "matlab/data/MOCAP_POSE_DATA_matlab.txt",
    "content": "3606 0.004587 -0.094220 -1.468240 0.866052 0.028918 0.049933 0.997198 -0.047600\n3607 0.013381 -0.094171 -1.468645 0.866101 0.029429 0.049597 0.997200 -0.047600\n3608 0.021259 -0.094150 -1.468468 0.866059 0.029742 0.049973 0.997171 -0.047622\n3609 0.028713 -0.094179 -1.469213 0.866074 0.029040 0.050119 0.997187 -0.047569\n3610 0.038268 -0.093928 -1.468376 0.866039 0.030747 0.049680 0.997156 -0.047617\n3611 0.046370 -0.093872 -1.469083 0.865883 0.031843 0.048793 0.997194 -0.046995\n3612 0.054126 -0.093837 -1.468681 0.866069 0.031558 0.048520 0.997195 -0.047465\n3613 0.064435 -0.093943 -1.468582 0.866094 0.031031 0.048807 0.997197 -0.047477\n3614 0.071197 -0.093822 -1.468628 0.866057 0.031623 0.048390 0.997199 -0.047468\n3615 0.078832 -0.094017 -1.468802 0.866074 0.031065 0.048753 0.997194 -0.047562\n3616 0.088224 -0.094229 -1.468336 0.866044 0.029064 0.050040 0.997191 -0.047558\n3617 0.095935 -0.094045 -1.468642 0.866114 0.030474 0.049073 0.997198 -0.047540\n3618 0.104713 -0.094222 -1.468315 0.866052 0.029136 0.049961 0.997191 -0.047591\n3619 0.113438 -0.094258 -1.468350 0.866025 0.028606 0.050078 0.997206 -0.047476\n3620 0.120247 -0.094229 -1.468345 0.866048 0.029126 0.049992 0.997191 -0.047563\n3621 0.130744 -0.094092 -1.468822 0.866110 0.030250 0.049250 0.997193 -0.047588\n3622 0.137865 -0.094133 -1.469197 0.866087 0.029308 0.050081 0.997181 -0.047570\n3623 0.147195 -0.094141 -1.468485 0.866095 0.029790 0.049375 0.997208 -0.047449\n3624 0.154726 -0.094153 -1.468804 0.866091 0.029491 0.049649 0.997194 -0.047632\n3625 0.162613 -0.094153 -1.469244 0.866091 0.029199 0.050075 0.997185 -0.047565\n3626 0.171207 -0.094209 -1.468330 0.866040 0.029230 0.049995 0.997188 -0.047569\n3627 0.179617 -0.094009 -1.469028 0.866117 0.030390 0.049391 0.997186 -0.047509\n3628 0.188154 -0.094269 -1.468308 0.866013 0.028310 0.050188 0.997208 -0.047495\n3629 0.196894 -0.094182 -1.468215 0.866063 0.029456 0.049856 0.997183 -0.047677\n3630 0.204867 -0.094278 -1.468373 0.866004 0.028310 0.050156 0.997213 -0.047426\n3631 0.213204 -0.093957 -1.468242 0.866068 0.030567 0.049091 0.997200 -0.047411\n3632 0.220513 -0.093593 -1.468639 0.865963 0.032053 0.048433 0.997205 -0.047000\n3633 0.228652 -0.094241 -1.468340 0.866045 0.028941 0.050025 0.997196 -0.047535\n3634 0.237865 -0.093792 -1.468808 0.866054 0.031788 0.048408 0.997191 -0.047493\n3635 0.247512 -0.094195 -1.468641 0.866081 0.029113 0.049758 0.997202 -0.047598\n3636 0.254745 -0.093988 -1.468399 0.866054 0.030583 0.049700 0.997161 -0.047585\n3637 0.262818 -0.094096 -1.468633 0.866101 0.030109 0.049164 0.997207 -0.047476\n3638 0.271578 -0.094186 -1.469228 0.866074 0.029051 0.050112 0.997186 -0.047587\n3639 0.278775 -0.094198 -1.468220 0.866059 0.029242 0.049910 0.997188 -0.047648\n3640 0.288210 -0.093938 -1.468404 0.866022 0.030787 0.049629 0.997160 -0.047559\n3641 0.296353 -0.093940 -1.468413 0.866065 0.030554 0.049829 0.997151 -0.047690\n3642 0.304840 -0.094029 -1.468469 0.866104 0.030360 0.049138 0.997202 -0.047464\n3643 0.313400 -0.094253 -1.468369 0.866018 0.028557 0.050086 0.997209 -0.047443\n3644 0.320244 -0.094217 -1.468436 0.866042 0.029255 0.050012 0.997188 -0.047528\n3645 0.330763 -0.094219 -1.468348 0.866047 0.029178 0.049988 0.997189 -0.047579\n3646 0.337925 -0.094002 -1.468266 0.866050 0.030596 0.049401 0.997175 -0.047592\n3647 0.346239 -0.094261 -1.468356 0.866031 0.028649 0.050130 0.997202 -0.047475\n3648 0.355943 -0.093837 -1.468666 0.865986 0.031255 0.049532 0.997156 -0.047438\n3649 0.363983 -0.093721 -1.468616 0.865949 0.031910 0.048937 0.997170 -0.047327\n3650 0.371692 -0.093688 -1.468432 0.866031 0.031794 0.048255 0.997206 -0.047339\n3651 0.379926 -0.094138 -1.469222 0.866085 0.029316 0.050085 0.997181 -0.047564\n3652 0.387812 -0.094097 -1.468655 0.866113 0.030090 0.049322 0.997196 -0.047559\n3653 0.396863 -0.094150 -1.468810 0.866103 0.029705 0.049537 0.997194 -0.047633\n3654 0.404934 -0.094054 -1.468650 0.866102 0.030337 0.049075 0.997205 -0.047477\n3655 0.412245 -0.093976 -1.468338 0.866047 0.030543 0.049819 0.997151 -0.047705\n3656 0.420851 -0.093894 -1.468545 0.865990 0.030997 0.049622 0.997157 -0.047492\n3657 0.428687 -0.094186 -1.468643 0.866071 0.029723 0.049377 0.997214 -0.047348\n3658 0.438746 -0.094222 -1.468307 0.866051 0.029100 0.049963 0.997192 -0.047602\n3659 0.445887 -0.094269 -1.468291 0.866008 0.028275 0.050208 0.997207 -0.047511\n3660 0.454389 -0.094018 -1.468179 0.866067 0.030220 0.049269 0.997200 -0.047444\n3661 0.464014 -0.094159 -1.468614 0.866098 0.029452 0.049612 0.997201 -0.047555\n3662 0.470199 -0.094263 -1.468308 0.866015 0.028464 0.050145 0.997205 -0.047517\n3663 0.480674 -0.094234 -1.468518 0.866046 0.028924 0.050042 0.997198 -0.047492\n3664 0.487846 -0.094050 -1.469188 0.866110 0.029721 0.050080 0.997169 -0.047559\n3665 0.496219 -0.094021 -1.468676 0.866099 0.030454 0.049013 0.997204 -0.047490\n3666 0.504918 -0.094070 -1.468613 0.866115 0.030228 0.049193 0.997201 -0.047513\n3667 0.513188 -0.093800 -1.468770 0.866051 0.031768 0.048448 0.997191 -0.047474\n3668 0.521681 -0.093660 -1.468520 0.865939 0.032103 0.048778 0.997171 -0.047341\n3669 0.529529 -0.094098 -1.468630 0.866097 0.030157 0.049122 0.997209 -0.047456\n3670 0.538298 -0.093841 -1.468484 0.866061 0.031473 0.048467 0.997200 -0.047470\n3671 0.546380 -0.094202 -1.468287 0.866046 0.029225 0.049941 0.997188 -0.047614\n3672 0.553421 -0.094271 -1.468332 0.866007 0.028349 0.050185 0.997208 -0.047484\n3673 0.561947 -0.094102 -1.468531 0.866081 0.030142 0.049214 0.997206 -0.047422\n3674 0.571384 -0.094086 -1.468642 0.866112 0.030153 0.049229 0.997200 -0.047527\n3675 0.578726 -0.094270 -1.468338 0.866020 0.028476 0.050135 0.997207 -0.047470\n3676 0.588189 -0.094074 -1.468345 0.866087 0.029926 0.049343 0.997203 -0.047497\n3677 0.596342 -0.094220 -1.468354 0.866049 0.029163 0.049982 0.997191 -0.047556\n3678 0.603647 -0.094019 -1.468878 0.866108 0.030444 0.049225 0.997191 -0.047539\n3679 0.611960 -0.093895 -1.468543 0.866072 0.031796 0.049012 0.997190 -0.046901\n3680 0.620091 -0.093815 -1.468950 0.866069 0.031086 0.048809 0.997209 -0.047172\n3681 0.630645 -0.093947 -1.468939 0.866101 0.030962 0.048965 0.997193 -0.047427\n3682 0.637667 -0.094269 -1.468363 0.866006 0.028381 0.050144 0.997210 -0.047464\n3683 0.645182 -0.093984 -1.468348 0.866051 0.030465 0.049851 0.997151 -0.047711\n3684 0.653653 -0.093802 -1.468566 0.866057 0.031583 0.048426 0.997200 -0.047439\n3685 0.663079 -0.094173 -1.468768 0.866086 0.029435 0.049636 0.997197 -0.047625\n3686 0.670172 -0.094205 -1.468264 0.866053 0.029254 0.049935 0.997187 -0.047641\n3687 0.679823 -0.093978 -1.468529 0.866070 0.030689 0.048872 0.997212 -0.047303\n3688 0.688393 -0.094146 -1.469243 0.866080 0.029214 0.050092 0.997184 -0.047565\n3689 0.695257 -0.093995 -1.468355 0.866056 0.030485 0.049771 0.997158 -0.047650\n3690 0.703648 -0.094203 -1.468647 0.866072 0.029095 0.049765 0.997201 -0.047611\n3691 0.713080 -0.094104 -1.468656 0.866108 0.029991 0.049369 0.997196 -0.047566\n3692 0.720202 -0.094161 -1.468652 0.866100 0.029532 0.049585 0.997198 -0.047597\n3693 0.728727 -0.094257 -1.468343 0.866017 0.028528 0.050122 0.997206 -0.047486\n3694 0.738856 -0.094055 -1.468652 0.866109 0.030452 0.049098 0.997197 -0.047545\n3695 0.745449 -0.094045 -1.468647 0.866110 0.030504 0.049102 0.997196 -0.047524\n3696 0.754876 -0.094107 -1.468405 0.866096 0.029746 0.049431 0.997204 -0.047503\n3697 0.762811 -0.093929 -1.468401 0.866016 0.030841 0.049606 0.997158 -0.047577\n3698 0.770309 -0.094188 -1.468710 0.866083 0.029198 0.049723 0.997200 -0.047616\n3699 0.779977 -0.094024 -1.468977 0.866113 0.030260 0.049394 0.997189 -0.047530\n3700 0.787755 -0.094065 -1.468643 0.866067 0.029963 0.049975 0.997168 -0.047556\n3701 0.795467 -0.094264 -1.468370 0.866028 0.028624 0.050110 0.997203 -0.047493\n3702 0.804308 -0.094090 -1.468352 0.866085 0.029821 0.049414 0.997202 -0.047504\n3703 0.813193 -0.094088 -1.468229 0.866058 0.030066 0.049854 0.997161 -0.047747\n3704 0.820308 -0.094068 -1.468659 0.866058 0.030668 0.048886 0.997209 -0.047374\n3705 0.829890 -0.094018 -1.469059 0.866105 0.030264 0.049465 0.997185 -0.047529\n3706 0.837573 -0.094119 -1.468625 0.866086 0.030027 0.049232 0.997208 -0.047443\n3707 0.846104 -0.094208 -1.468305 0.866051 0.029207 0.049953 0.997189 -0.047612\n3708 0.853558 -0.094098 -1.468767 0.866101 0.030247 0.049195 0.997198 -0.047553\n3709 0.863465 -0.094208 -1.468423 0.866049 0.029256 0.049989 0.997187 -0.047568\n3710 0.870450 -0.094228 -1.468342 0.866039 0.029091 0.050014 0.997191 -0.047561\n3711 0.880218 -0.094212 -1.468703 0.866060 0.028934 0.049859 0.997201 -0.047619\n3712 0.887951 -0.094179 -1.468358 0.866058 0.029553 0.049943 0.997177 -0.047653\n3713 0.895406 -0.093803 -1.468616 0.866058 0.031587 0.048410 0.997200 -0.047443\n3714 0.904886 -0.094114 -1.468200 0.866065 0.029854 0.049628 0.997184 -0.047648\n3715 0.912769 -0.094148 -1.468630 0.866086 0.029865 0.049283 0.997213 -0.047392\n3716 0.921619 -0.093863 -1.468579 0.865985 0.031115 0.049585 0.997155 -0.047494\n3717 0.930080 -0.094224 -1.468336 0.866032 0.029013 0.050027 0.997194 -0.047539\n3718 0.937117 -0.094266 -1.468345 0.866016 0.028539 0.050129 0.997206 -0.047474\n3719 0.947165 -0.094065 -1.468658 0.866110 0.030330 0.049211 0.997195 -0.047542\n3720 0.956765 -0.094188 -1.468649 0.866084 0.029296 0.049685 0.997200 -0.047596\n3721 0.963720 -0.094192 -1.468502 0.866048 0.029405 0.050008 0.997182 -0.047565\n3722 0.971748 -0.094016 -1.468632 0.866102 0.030656 0.049012 0.997196 -0.047511\n3723 0.979633 -0.093827 -1.468693 0.866062 0.031546 0.048511 0.997196 -0.047448\n3724 0.988125 -0.094204 -1.468323 0.866037 0.029266 0.050002 0.997186 -0.047577\n3725 0.996593 -0.093743 -1.468604 0.865932 0.031787 0.049041 0.997166 -0.047384\n3726 1.003630 -0.094027 -1.468608 0.866104 0.030516 0.049024 0.997201 -0.047493\n3727 1.012463 -0.094264 -1.468357 0.866014 0.028554 0.050142 0.997205 -0.047454\n3728 1.021086 -0.094264 -1.468332 0.866007 0.028448 0.050174 0.997206 -0.047475\n3729 1.028725 -0.094249 -1.468388 0.866027 0.028833 0.050072 0.997199 -0.047485\n3730 1.038780 -0.093818 -1.468672 0.866056 0.031584 0.048481 0.997196 -0.047464\n3731 1.046200 -0.094205 -1.468633 0.866066 0.028984 0.049841 0.997202 -0.047581\n3732 1.053569 -0.094105 -1.468605 0.866106 0.029895 0.049365 0.997200 -0.047555\n3733 1.062741 -0.094271 -1.468365 0.866015 0.028474 0.050099 0.997210 -0.047445\n3734 1.073212 -0.094267 -1.468315 0.866005 0.028330 0.050199 0.997207 -0.047498\n3735 1.080280 -0.094089 -1.469107 0.866120 0.030538 0.049527 0.997182 -0.047363\n3736 1.086985 -0.094048 -1.469221 0.866108 0.029682 0.050062 0.997172 -0.047548\n3737 1.097926 -0.093883 -1.469090 0.865878 0.031853 0.048795 0.997191 -0.047066\n3738 1.106361 -0.094222 -1.468464 0.866034 0.029167 0.050008 0.997191 -0.047528\n3739 1.114119 -0.094180 -1.468299 0.866048 0.029456 0.049921 0.997181 -0.047655\n3740 1.121976 -0.094270 -1.468344 0.866016 0.028544 0.050147 0.997205 -0.047458\n3741 1.130390 -0.094261 -1.468343 0.866014 0.028472 0.050130 0.997207 -0.047482\n3742 1.137989 -0.094262 -1.468366 0.866020 0.028634 0.050087 0.997205 -0.047478\n3743 1.150706 -0.094078 -1.468810 0.866090 0.030519 0.049109 0.997194 -0.047555\n3744 1.153881 -0.094056 -1.468595 0.866104 0.030314 0.049179 0.997199 -0.047512\n3745 1.162647 -0.094264 -1.468336 0.866012 0.028488 0.050125 0.997207 -0.047486\n3746 1.170675 -0.094071 -1.468394 0.866057 0.030186 0.049908 0.997158 -0.047691\n3747 1.178535 -0.094252 -1.468378 0.866036 0.028689 0.050011 0.997205 -0.047525\n3748 1.188268 -0.094256 -1.468349 0.866017 0.028579 0.050108 0.997205 -0.047477\n3749 1.197296 -0.093797 -1.468466 0.866090 0.030606 0.048830 0.997257 -0.046442\n3750 1.203585 -0.093885 -1.468515 0.866064 0.031320 0.048588 0.997197 -0.047502\n3751 1.211687 -0.094245 -1.468510 0.866041 0.028796 0.050042 0.997201 -0.047502\n3752 1.221516 -0.094208 -1.468327 0.866051 0.029203 0.049961 0.997188 -0.047609\n3753 1.229796 -0.093895 -1.468570 0.866072 0.031316 0.048629 0.997197 -0.047465\n3754 1.236810 -0.094268 -1.468373 0.866011 0.028471 0.050121 0.997210 -0.047439\n3755 1.245194 -0.093957 -1.468389 0.866039 0.030559 0.049815 0.997151 -0.047684\n3756 1.255514 -0.093804 -1.468981 0.866062 0.031120 0.048745 0.997212 -0.047154\n3757 1.262296 -0.094006 -1.468644 0.866101 0.030691 0.048952 0.997199 -0.047498\n3758 1.271494 -0.094236 -1.468410 0.866030 0.028939 0.050004 0.997199 -0.047490\n3759 1.280003 -0.094262 -1.468334 0.866001 0.028442 0.050191 0.997205 -0.047470\n3760 1.286942 -0.094018 -1.468405 0.866046 0.030489 0.049746 0.997161 -0.047604\n3761 1.295122 -0.094124 -1.468660 0.866063 0.030258 0.049084 0.997213 -0.047345\n3762 1.304881 -0.094118 -1.468634 0.866055 0.029761 0.049980 0.997174 -0.047549\n3763 1.313425 -0.094130 -1.468663 0.866095 0.029758 0.049462 0.997198 -0.047586\n3764 1.321467 -0.094088 -1.468306 0.866076 0.030145 0.049397 0.997189 -0.047589\n3765 1.330108 -0.094231 -1.468469 0.866033 0.028980 0.050061 0.997195 -0.047494\n3766 1.336949 -0.094149 -1.468670 0.866099 0.029748 0.049432 0.997199 -0.047590\n3767 1.346722 -0.093959 -1.468315 0.866028 0.030608 0.049655 0.997161 -0.047622\n3768 1.354275 -0.094267 -1.468372 0.866012 0.028585 0.050111 0.997207 -0.047429\n3769 1.361846 -0.094269 -1.468345 0.866002 0.028364 0.050147 0.997210 -0.047475\n3770 1.370812 -0.094064 -1.468646 0.866108 0.030344 0.049167 0.997198 -0.047524\n3771 1.380076 -0.093799 -1.469203 0.866081 0.031353 0.048808 0.997202 -0.047156\n3772 1.387940 -0.094217 -1.468236 0.866049 0.028978 0.049952 0.997195 -0.047614\n3773 1.397547 -0.093727 -1.468833 0.865936 0.031756 0.049218 0.997161 -0.047329\n3774 1.404333 -0.093697 -1.468726 0.865945 0.031972 0.049177 0.997148 -0.047482\n3775 1.411945 -0.094140 -1.468597 0.866100 0.029655 0.049429 0.997204 -0.047559\n3776 1.421608 -0.094094 -1.469177 0.866079 0.029437 0.050118 0.997175 -0.047575\n3777 1.429464 -0.094002 -1.468982 0.866024 0.031168 0.048945 0.997222 -0.046698\n3778 1.438266 -0.094253 -1.468352 0.866017 0.028601 0.050157 0.997203 -0.047471\n3779 1.446862 -0.094205 -1.468690 0.866057 0.028947 0.049919 0.997198 -0.047605\n3780 1.453659 -0.094226 -1.468488 0.866042 0.029060 0.050032 0.997193 -0.047517\n3781 1.462168 -0.094206 -1.468714 0.866071 0.029042 0.049786 0.997201 -0.047627\n3782 1.471661 -0.094260 -1.468332 0.866002 0.028405 0.050165 0.997207 -0.047494\n3783 1.479711 -0.094254 -1.468378 0.866023 0.028691 0.050070 0.997204 -0.047485\n3784 1.488386 -0.093823 -1.468547 0.866052 0.031526 0.048459 0.997199 -0.047456\n3785 1.496405 -0.094002 -1.468991 0.866099 0.030602 0.049212 0.997187 -0.047530\n3786 1.504659 -0.093988 -1.468728 0.866086 0.030600 0.048979 0.997202 -0.047456\n3787 1.513100 -0.094162 -1.468192 0.866051 0.029473 0.049792 0.997187 -0.047641\n3788 1.520311 -0.094278 -1.468310 0.865988 0.028156 0.050229 0.997210 -0.047508\n3789 1.529133 -0.094250 -1.468380 0.866019 0.028710 0.050082 0.997203 -0.047480\n3790 1.537763 -0.094251 -1.468357 0.866009 0.028677 0.050130 0.997203 -0.047434\n3791 1.546783 -0.093805 -1.468484 0.866048 0.031576 0.048411 0.997201 -0.047438\n3792 1.554262 -0.093839 -1.468351 0.866046 0.031217 0.048652 0.997204 -0.047369\n3793 1.562280 -0.094087 -1.468789 0.866088 0.030415 0.049115 0.997197 -0.047539\n3794 1.571218 -0.093827 -1.468548 0.866053 0.031527 0.048426 0.997199 -0.047484\n3795 1.580119 -0.093885 -1.468789 0.865927 0.031269 0.049032 0.997206 -0.046891\n3796 1.586942 -0.094156 -1.468658 0.866096 0.029630 0.049506 0.997200 -0.047585\n3797 1.595187 -0.094066 -1.468291 0.866068 0.030252 0.049421 0.997184 -0.047606\n3798 1.604611 -0.094036 -1.469169 0.866099 0.029763 0.050104 0.997167 -0.047569\n3799 1.613171 -0.093855 -1.468644 0.866041 0.031540 0.048981 0.997183 -0.047244\n3800 1.621450 -0.093841 -1.468445 0.866056 0.031259 0.048620 0.997202 -0.047396\n3801 1.630815 -0.093836 -1.468588 0.866054 0.031481 0.048479 0.997200 -0.047449\n3802 1.637104 -0.094026 -1.468248 0.866037 0.030369 0.049616 0.997168 -0.047657\n3803 1.647241 -0.094247 -1.468374 0.866024 0.028890 0.050050 0.997198 -0.047510\n3804 1.654255 -0.094254 -1.468364 0.866014 0.028682 0.050119 0.997201 -0.047487\n3805 1.661990 -0.094018 -1.468462 0.866090 0.030430 0.049089 0.997202 -0.047472\n3806 1.670743 -0.094018 -1.469234 0.866113 0.029833 0.050153 0.997160 -0.047600\n3807 1.680003 -0.094281 -1.468323 0.865989 0.028215 0.050230 0.997209 -0.047489\n3808 1.687015 -0.094254 -1.468355 0.866010 0.028586 0.050119 0.997205 -0.047469\n3809 1.695129 -0.093828 -1.468527 0.866041 0.031624 0.048386 0.997198 -0.047486\n3810 1.705582 -0.093898 -1.468543 0.866068 0.031262 0.048627 0.997198 -0.047473\n3811 1.712209 -0.094221 -1.468336 0.866024 0.029147 0.050006 0.997190 -0.047561\n3812 1.721388 -0.093822 -1.468469 0.866046 0.031523 0.048452 0.997199 -0.047461\n3813 1.730104 -0.094096 -1.468655 0.866100 0.030099 0.049254 0.997199 -0.047559\n3814 1.737094 -0.094190 -1.468405 0.866065 0.029269 0.049723 0.997200 -0.047578\n3815 1.745337 -0.094024 -1.468997 0.866032 0.031167 0.048968 0.997218 -0.046763\n3816 1.755727 -0.093999 -1.469041 0.866106 0.030456 0.049359 0.997185 -0.047516\n3817 1.762314 -0.094244 -1.468372 0.866018 0.028760 0.050091 0.997201 -0.047478\n3818 1.771778 -0.094263 -1.468352 0.866014 0.028569 0.050112 0.997205 -0.047477\n3819 1.780026 -0.094250 -1.468366 0.866016 0.028697 0.050106 0.997202 -0.047474\n3820 1.786931 -0.094259 -1.468356 0.866007 0.028584 0.050134 0.997204 -0.047466\n3821 1.797170 -0.094106 -1.468657 0.866102 0.030056 0.049337 0.997196 -0.047578\n3822 1.804334 -0.094225 -1.468410 0.866023 0.029058 0.050050 0.997193 -0.047508\n3823 1.811966 -0.094172 -1.468663 0.866082 0.029411 0.049642 0.997198 -0.047606\n3824 1.820254 -0.094141 -1.469006 0.866212 0.030439 0.049497 0.997205 -0.046962\n3825 1.830529 -0.094194 -1.468719 0.866067 0.029170 0.049776 0.997198 -0.047623\n3826 1.836993 -0.094116 -1.468813 0.866092 0.029861 0.049493 0.997192 -0.047617\n3827 1.845491 -0.094153 -1.468414 0.866042 0.029748 0.049988 0.997168 -0.047660\n3828 1.854455 -0.093993 -1.469278 0.866128 0.029952 0.050205 0.997153 -0.047621\n3829 1.861937 -0.094129 -1.468196 0.866054 0.029812 0.049696 0.997181 -0.047664\n3830 1.871775 -0.093859 -1.468637 0.866063 0.031356 0.048612 0.997197 -0.047449\n3831 1.879054 -0.094156 -1.469206 0.866061 0.029201 0.050124 0.997182 -0.047563\n3832 1.888791 -0.093877 -1.468549 0.865983 0.031022 0.049644 0.997155 -0.047497\n3833 1.896136 -0.094043 -1.468977 0.866064 0.031107 0.048993 0.997221 -0.046714\n3834 1.904815 -0.094072 -1.469120 0.866209 0.030259 0.049835 0.997177 -0.047307\n3835 1.913787 -0.093832 -1.468537 0.866046 0.031499 0.048523 0.997197 -0.047454\n3836 1.920188 -0.094039 -1.468645 0.866097 0.030514 0.049084 0.997196 -0.047535\n3837 1.931161 -0.094101 -1.468834 0.866213 0.030589 0.049715 0.997180 -0.047177\n3838 1.938051 -0.094268 -1.468346 0.866006 0.028464 0.050130 0.997208 -0.047469\n3839 1.945064 -0.094042 -1.468646 0.866097 0.030442 0.049115 0.997197 -0.047526\n3840 1.954036 -0.094217 -1.468331 0.866036 0.029176 0.050002 0.997188 -0.047594\n3841 1.964768 -0.093960 -1.468365 0.866031 0.030565 0.049839 0.997150 -0.047683\n3842 1.971057 -0.094038 -1.468238 0.866038 0.030303 0.049643 0.997168 -0.047668\n3843 1.980344 -0.094070 -1.468518 0.866054 0.029925 0.050026 0.997161 -0.047656\n3844 1.987583 -0.094217 -1.468492 0.866035 0.029186 0.050050 0.997188 -0.047522\n3845 1.998169 -0.093812 -1.468356 0.866033 0.031278 0.048612 0.997206 -0.047319\n3846 2.004635 -0.094265 -1.468340 0.866004 0.028499 0.050127 0.997206 -0.047486\n3847 2.011790 -0.094226 -1.468410 0.866022 0.028994 0.050055 0.997195 -0.047491\n3848 2.019995 -0.094087 -1.468955 0.866092 0.029803 0.049601 0.997189 -0.047598\n3849 2.028562 -0.093856 -1.468545 0.866057 0.031384 0.048594 0.997197 -0.047458\n3850 2.038404 -0.094198 -1.468661 0.866062 0.029031 0.049813 0.997200 -0.047625\n3851 2.046868 -0.094016 -1.468954 0.866103 0.030347 0.049325 0.997190 -0.047519\n3852 2.054503 -0.093882 -1.468557 0.866060 0.031262 0.048648 0.997198 -0.047463\n3853 2.064424 -0.094039 -1.468354 0.866047 0.030369 0.049863 0.997155 -0.047683\n3854 2.070209 -0.094206 -1.468702 0.866046 0.028915 0.049969 0.997194 -0.047648\n3855 2.080188 -0.094169 -1.468645 0.866066 0.029842 0.049309 0.997214 -0.047354\n3856 2.087612 -0.093806 -1.468592 0.866038 0.031682 0.048351 0.997197 -0.047497\n3857 2.095325 -0.094263 -1.468340 0.866012 0.028543 0.050116 0.997205 -0.047506\n3858 2.103413 -0.094244 -1.468368 0.866013 0.028700 0.050102 0.997202 -0.047475\n3859 2.113369 -0.094206 -1.468363 0.866040 0.029299 0.050020 0.997183 -0.047607\n3860 2.120589 -0.094237 -1.468417 0.866028 0.028904 0.049996 0.997200 -0.047513\n3861 2.128571 -0.093818 -1.468629 0.866041 0.031625 0.048435 0.997196 -0.047477\n3862 2.138767 -0.094224 -1.468463 0.866036 0.029142 0.050029 0.997191 -0.047518\n3863 2.146221 -0.094003 -1.468374 0.866057 0.030735 0.049111 0.997187 -0.047554\n3864 2.153392 -0.093920 -1.469130 0.866082 0.031189 0.048949 0.997189 -0.047380\n3865 2.164169 -0.093816 -1.468542 0.866051 0.031502 0.048473 0.997199 -0.047453\n3866 2.171646 -0.094232 -1.468361 0.866035 0.029075 0.050019 0.997191 -0.047564\n3867 2.180754 -0.094105 -1.468663 0.866101 0.030018 0.049332 0.997198 -0.047562\n3868 2.187370 -0.093958 -1.469108 0.866101 0.030545 0.049350 0.997186 -0.047458\n3869 2.195359 -0.093881 -1.469096 0.866090 0.030989 0.048987 0.997197 -0.047310\n3870 2.204471 -0.093981 -1.468245 0.866064 0.030389 0.049143 0.997203 -0.047420\n3871 2.213675 -0.094189 -1.468717 0.866062 0.029145 0.049820 0.997196 -0.047632\n3872 2.220150 -0.093713 -1.468493 0.866022 0.031803 0.048291 0.997202 -0.047379\n3873 2.228423 -0.094243 -1.468431 0.866035 0.028817 0.050049 0.997200 -0.047506\n3874 2.238937 -0.094229 -1.468491 0.866026 0.028649 0.050044 0.997202 -0.047581\n3875 2.246269 -0.094067 -1.468550 0.866059 0.029949 0.050039 0.997162 -0.047622\n3876 2.253448 -0.094257 -1.468319 0.866010 0.028428 0.050116 0.997207 -0.047513\n3877 2.262045 -0.094246 -1.468379 0.866020 0.028779 0.050079 0.997200 -0.047490\n3878 2.271971 -0.094016 -1.468644 0.866097 0.030627 0.049021 0.997197 -0.047505\n3879 2.279952 -0.093779 -1.468382 0.866032 0.031566 0.048402 0.997202 -0.047425\n3880 2.287982 -0.093937 -1.468576 0.866081 0.030910 0.048848 0.997200 -0.047445\n3881 2.297222 -0.094225 -1.468329 0.866040 0.029049 0.050010 0.997192 -0.047575\n3882 2.303641 -0.093870 -1.468483 0.866057 0.031295 0.048620 0.997198 -0.047470\n3883 2.314972 -0.094267 -1.468301 0.865998 0.028320 0.050179 0.997207 -0.047515\n3884 2.321108 -0.093982 -1.468322 0.866041 0.030447 0.049834 0.997153 -0.047711\n3885 2.329009 -0.093641 -1.468678 0.865954 0.032106 0.048760 0.997179 -0.047182\n3886 2.337891 -0.093781 -1.468471 0.866032 0.031680 0.048373 0.997199 -0.047434\n3887 2.345953 -0.094222 -1.468452 0.866028 0.029085 0.050006 0.997194 -0.047512\n3888 2.354600 -0.094257 -1.468372 0.866016 0.028695 0.050088 0.997203 -0.047487\n3889 2.363491 -0.094170 -1.468663 0.866079 0.029412 0.049632 0.997199 -0.047609\n3890 2.370673 -0.094266 -1.468315 0.866001 0.028394 0.050179 0.997206 -0.047507\n3891 2.378669 -0.093808 -1.468824 0.866017 0.031858 0.048359 0.997189 -0.047549\n3892 2.388384 -0.093892 -1.468839 0.866070 0.030906 0.048861 0.997205 -0.047323\n3893 2.396201 -0.093800 -1.468617 0.866045 0.031626 0.048434 0.997196 -0.047469\n3894 2.404867 -0.094137 -1.468251 0.866041 0.029860 0.049913 0.997165 -0.047745\n3895 2.412371 -0.093942 -1.469040 0.866090 0.030977 0.049069 0.997187 -0.047445\n3896 2.421224 -0.093881 -1.468634 0.866067 0.031289 0.048649 0.997197 -0.047452\n3897 2.428466 -0.094072 -1.468649 0.866088 0.030252 0.049148 0.997203 -0.047494\n3898 2.438761 -0.094083 -1.468638 0.866083 0.030260 0.049140 0.997204 -0.047484\n3899 2.445381 -0.094055 -1.468645 0.866100 0.030386 0.049135 0.997198 -0.047528\n3900 2.454754 -0.093779 -1.468364 0.866027 0.031471 0.048491 0.997204 -0.047365\n3901 2.463047 -0.094020 -1.468406 0.866040 0.030477 0.049762 0.997161 -0.047581\n3902 2.471099 -0.093804 -1.468725 0.866037 0.031647 0.048424 0.997195 -0.047495\n3903 2.480082 -0.094273 -1.468355 0.866000 0.028418 0.050147 0.997208 -0.047467\n3904 2.487501 -0.094068 -1.468656 0.866094 0.030262 0.049218 0.997196 -0.047550\n3905 2.495180 -0.094072 -1.468643 0.866082 0.030238 0.049123 0.997205 -0.047481\n3906 2.503851 -0.093911 -1.468365 0.866020 0.030758 0.049651 0.997158 -0.047599\n3907 2.512581 -0.093974 -1.468369 0.866057 0.030900 0.049031 0.997186 -0.047554\n3908 2.520936 -0.094251 -1.468359 0.866002 0.028575 0.050112 0.997205 -0.047489\n3909 2.529332 -0.094109 -1.468663 0.866095 0.030040 0.049329 0.997197 -0.047563\n3910 2.537581 -0.094019 -1.468670 0.866081 0.030495 0.049026 0.997202 -0.047478\n3911 2.545175 -0.094019 -1.468651 0.866090 0.030630 0.049026 0.997197 -0.047509\n3912 2.556075 -0.094228 -1.468409 0.866017 0.029027 0.050070 0.997194 -0.047491\n3913 2.562365 -0.094244 -1.468415 0.866020 0.028890 0.050040 0.997199 -0.047499\n3914 2.571537 -0.094262 -1.468351 0.866000 0.028545 0.050179 0.997203 -0.047467\n3915 2.578861 -0.094025 -1.468993 0.866057 0.031050 0.048925 0.997187 -0.047550\n3916 2.586830 -0.094282 -1.468349 0.865993 0.028318 0.050197 0.997209 -0.047463\n3917 2.597166 -0.094132 -1.468528 0.866069 0.029789 0.049376 0.997209 -0.047424\n3918 2.604432 -0.094264 -1.468382 0.866002 0.028566 0.050094 0.997208 -0.047442\n3919 2.613375 -0.093944 -1.468349 0.866017 0.030619 0.049714 0.997158 -0.047619\n3920 2.621233 -0.094263 -1.468357 0.866003 0.028534 0.050136 0.997206 -0.047468\n3921 2.631266 -0.094255 -1.468350 0.866000 0.028507 0.050172 0.997204 -0.047473\n3922 2.637471 -0.094282 -1.468357 0.865983 0.028282 0.050224 0.997209 -0.047462\n3923 2.645793 -0.094086 -1.468260 0.866052 0.030088 0.049552 0.997182 -0.047615\n3924 2.653371 -0.094219 -1.468729 0.866045 0.028850 0.049930 0.997198 -0.047647\n3925 2.662332 -0.093797 -1.468530 0.866070 0.030613 0.048867 0.997262 -0.046303\n3926 2.671215 -0.094206 -1.468352 0.866020 0.029228 0.050030 0.997186 -0.047572\n3927 2.678484 -0.094219 -1.468709 0.866050 0.028916 0.049915 0.997197 -0.047646\n3928 2.687989 -0.094233 -1.468393 0.866016 0.028936 0.050069 0.997195 -0.047518\n3929 2.695863 -0.094205 -1.468736 0.866062 0.029133 0.049831 0.997195 -0.047646\n3930 2.704744 -0.094188 -1.468373 0.866022 0.029412 0.050013 0.997180 -0.047608\n3931 2.712075 -0.094087 -1.468291 0.866061 0.030108 0.049454 0.997187 -0.047599\n3932 2.721555 -0.094105 -1.468558 0.866084 0.029860 0.049389 0.997200 -0.047546\n3933 2.728607 -0.094109 -1.469217 0.866080 0.029462 0.050120 0.997175 -0.047566\n3934 2.738233 -0.094203 -1.468206 0.866010 0.029129 0.050027 0.997188 -0.047599\n3935 2.746534 -0.094153 -1.468158 0.866037 0.029599 0.049841 0.997178 -0.047697\n3936 2.754472 -0.094222 -1.468416 0.866018 0.029063 0.050077 0.997192 -0.047500\n3937 2.764035 -0.093847 -1.468685 0.865945 0.031242 0.049575 0.997154 -0.047439\n3938 2.771009 -0.094020 -1.468270 0.866026 0.030368 0.049740 0.997161 -0.047689\n3939 2.779751 -0.093994 -1.468260 0.866034 0.030466 0.049827 0.997150 -0.047765\n3940 2.787632 -0.094220 -1.468686 0.866047 0.028895 0.049946 0.997198 -0.047617\n3941 2.795161 -0.094262 -1.468357 0.865998 0.028488 0.050144 0.997208 -0.047444\n3942 2.803595 -0.094263 -1.468349 0.865987 0.028453 0.050206 0.997206 -0.047441\n3943 2.812294 -0.094249 -1.468368 0.866008 0.028755 0.050121 0.997199 -0.047487\n3944 2.821195 -0.094244 -1.468364 0.866011 0.028876 0.050061 0.997198 -0.047493\n3945 2.829400 -0.094143 -1.469175 0.866053 0.029244 0.050146 0.997179 -0.047580\n3946 2.837480 -0.094054 -1.468656 0.866092 0.030445 0.049140 0.997196 -0.047529\n3947 2.845231 -0.094187 -1.468799 0.866055 0.028994 0.049916 0.997194 -0.047670\n3948 2.855407 -0.094195 -1.468072 0.866313 0.030028 0.048913 0.997305 -0.045711\n3949 2.862628 -0.093799 -1.468622 0.866025 0.031794 0.048335 0.997193 -0.047524\n3950 2.871387 -0.094001 -1.468694 0.866074 0.030483 0.048981 0.997205 -0.047464\n3951 2.879057 -0.094120 -1.468607 0.866090 0.029836 0.049417 0.997199 -0.047550\n3952 2.887491 -0.093779 -1.468753 0.865944 0.031471 0.049428 0.997155 -0.047409\n3953 2.895301 -0.094212 -1.468402 0.866045 0.029014 0.049889 0.997198 -0.047600\n3954 2.905795 -0.094231 -1.468386 0.866027 0.028724 0.049958 0.997204 -0.047572\n3955 2.913430 -0.093993 -1.469258 0.866131 0.029976 0.050181 0.997154 -0.047612\n3956 2.921321 -0.094138 -1.468635 0.866066 0.029962 0.049214 0.997214 -0.047384\n3957 2.931157 -0.094236 -1.468432 0.866022 0.029037 0.050056 0.997193 -0.047524\n3958 2.937347 -0.094118 -1.468657 0.866091 0.029899 0.049386 0.997198 -0.047576\n3959 2.947186 -0.094265 -1.468354 0.866003 0.028532 0.050109 0.997206 -0.047481\n3960 2.954519 -0.094024 -1.468273 0.866040 0.030359 0.049866 0.997151 -0.047769\n3961 2.961920 -0.094027 -1.468988 0.866040 0.031109 0.048847 0.997188 -0.047563\n3962 2.970119 -0.094220 -1.468341 0.866021 0.029117 0.050036 0.997189 -0.047562\n3963 2.979111 -0.094154 -1.469235 0.866063 0.029178 0.050104 0.997183 -0.047577\n3964 2.988098 -0.094243 -1.468407 0.866015 0.028908 0.050070 0.997196 -0.047513\n3965 2.995234 -0.094278 -1.468341 0.865975 0.028221 0.050242 0.997209 -0.047476\n3966 3.004994 -0.094015 -1.468280 0.866027 0.030341 0.049878 0.997152 -0.047742\n3967 3.012319 -0.093975 -1.468271 0.866010 0.030626 0.049479 0.997170 -0.047596\n3968 3.021346 -0.094197 -1.468660 0.866062 0.029207 0.049759 0.997198 -0.047619\n3969 3.031550 -0.093913 -1.468687 0.866057 0.031050 0.048743 0.997203 -0.047397\n3970 3.037892 -0.093989 -1.468305 0.866022 0.030452 0.049780 0.997155 -0.047710\n3971 3.052078 -0.093791 -1.468575 0.866019 0.031786 0.048309 0.997195 -0.047513\n3972 3.055303 -0.094259 -1.468362 0.866000 0.028637 0.050134 0.997202 -0.047494\n3973 3.062418 -0.093844 -1.468686 0.865948 0.031273 0.049517 0.997157 -0.047413\n3974 3.070169 -0.094220 -1.468470 0.866021 0.029156 0.050028 0.997190 -0.047527\n3975 3.080126 -0.094028 -1.468970 0.866036 0.031128 0.048978 0.997220 -0.046735\n3976 3.087378 -0.093793 -1.468600 0.866035 0.031611 0.048416 0.997199 -0.047437\n3977 3.095473 -0.094256 -1.468369 0.866001 0.028679 0.050111 0.997202 -0.047493\n3978 3.103426 -0.093962 -1.469012 0.866059 0.031142 0.048869 0.997190 -0.047473\n3979 3.112557 -0.094279 -1.468324 0.865988 0.028306 0.050189 0.997209 -0.047482\n3980 3.121513 -0.094130 -1.468801 0.866080 0.029823 0.049507 0.997192 -0.047631\n3981 3.130798 -0.094239 -1.468602 0.866024 0.028715 0.050005 0.997198 -0.047658\n3982 3.137221 -0.094273 -1.468341 0.865994 0.028417 0.050148 0.997207 -0.047486\n3983 3.145298 -0.094266 -1.468361 0.866004 0.028620 0.050100 0.997206 -0.047457\n3984 3.154049 -0.093943 -1.469115 0.866091 0.030705 0.049283 0.997186 -0.047426\n3985 3.162587 -0.094149 -1.469216 0.866060 0.029186 0.050123 0.997183 -0.047557\n3986 3.171612 -0.094087 -1.469141 0.866072 0.029568 0.050120 0.997172 -0.047566\n3987 3.178665 -0.094095 -1.468659 0.866090 0.030117 0.049322 0.997195 -0.047568\n3988 3.187880 -0.094041 -1.468903 0.866044 0.031076 0.048857 0.997188 -0.047580\n3989 3.195535 -0.093985 -1.468722 0.866069 0.030582 0.048973 0.997204 -0.047444\n3990 3.204837 -0.094219 -1.468690 0.866050 0.028922 0.049893 0.997199 -0.047634\n3991 3.212864 -0.094241 -1.468386 0.866005 0.028810 0.050109 0.997198 -0.047490\n3992 3.221422 -0.094195 -1.468507 0.866029 0.029478 0.050034 0.997178 -0.047584\n3993 3.228996 -0.094264 -1.468349 0.866001 0.028542 0.050105 0.997206 -0.047495\n3994 3.238017 -0.094189 -1.468658 0.866063 0.029252 0.049700 0.997200 -0.047609\n3995 3.246536 -0.094113 -1.468588 0.866084 0.029846 0.049451 0.997198 -0.047549\n3996 3.254789 -0.094183 -1.468662 0.866051 0.029772 0.049329 0.997218 -0.047298\n3997 3.262845 -0.094264 -1.468321 0.865976 0.028317 0.050262 0.997204 -0.047503\n3998 3.271304 -0.093988 -1.468635 0.866079 0.030819 0.048933 0.997196 -0.047498\n3999 3.278668 -0.094251 -1.468365 0.866005 0.028728 0.050098 0.997201 -0.047480\n4000 3.288876 -0.094275 -1.468335 0.865992 0.028325 0.050181 0.997208 -0.047499\n4001 3.296417 -0.094114 -1.468661 0.866094 0.029994 0.049352 0.997197 -0.047576\n4002 3.304805 -0.094100 -1.468313 0.866053 0.030051 0.049464 0.997188 -0.047606\n4003 3.313288 -0.094086 -1.468480 0.866069 0.030160 0.049301 0.997201 -0.047442\n4004 3.321745 -0.093833 -1.468449 0.866035 0.031348 0.048632 0.997199 -0.047392\n4005 3.330292 -0.094091 -1.468282 0.866045 0.030111 0.049528 0.997182 -0.047623\n4006 3.338038 -0.094237 -1.468415 0.866010 0.028871 0.050073 0.997198 -0.047499\n4007 3.345727 -0.094213 -1.468718 0.866035 0.028922 0.049926 0.997196 -0.047645\n4008 3.353609 -0.094267 -1.468338 0.865986 0.028440 0.050176 0.997205 -0.047484\n4009 3.362640 -0.094081 -1.468660 0.866086 0.030248 0.049242 0.997195 -0.047573\n4010 3.371489 -0.094270 -1.468315 0.865979 0.028265 0.050253 0.997205 -0.047510\n4011 3.378811 -0.094021 -1.468679 0.866072 0.030521 0.049006 0.997203 -0.047473\n4012 3.389769 -0.093976 -1.468368 0.866046 0.030884 0.049054 0.997185 -0.047558\n4013 3.395717 -0.093791 -1.468657 0.866016 0.031793 0.048364 0.997193 -0.047512\n4014 3.404974 -0.093806 -1.468710 0.866026 0.031695 0.048425 0.997194 -0.047491\n4015 3.413456 -0.093885 -1.468560 0.866050 0.031291 0.048673 0.997195 -0.047473\n4016 3.421364 -0.094102 -1.468631 0.866036 0.029861 0.050008 0.997169 -0.047554\n4017 3.428689 -0.094264 -1.468327 0.865985 0.028313 0.050170 0.997209 -0.047488\n4018 3.438476 -0.093826 -1.468543 0.866028 0.031582 0.048439 0.997196 -0.047494\n4019 3.446411 -0.093894 -1.468493 0.865969 0.030971 0.049657 0.997156 -0.047497\n4020 3.454662 -0.093982 -1.468624 0.866076 0.030855 0.048906 0.997195 -0.047513\n4021 3.462589 -0.093894 -1.468772 0.865908 0.031255 0.049033 0.997207 -0.046880\n4022 3.471249 -0.094238 -1.468448 0.866017 0.028965 0.050003 0.997198 -0.047506\n4023 3.480574 -0.094001 -1.469081 0.866089 0.030307 0.049438 0.997187 -0.047496\n4024 3.487405 -0.094221 -1.468329 0.866022 0.028899 0.050005 0.997196 -0.047585\n4025 3.495707 -0.094135 -1.468631 0.866072 0.029978 0.049243 0.997210 -0.047420\n4026 3.504573 -0.093835 -1.468500 0.866035 0.031458 0.048528 0.997197 -0.047464\n4027 3.512633 -0.094096 -1.468635 0.866037 0.029911 0.050020 0.997167 -0.047559\n4028 3.521650 -0.094274 -1.468361 0.865979 0.028270 0.050210 0.997210 -0.047452\n4029 3.528836 -0.093985 -1.468631 0.866074 0.030856 0.048906 0.997196 -0.047501\n4030 3.538618 -0.094263 -1.468346 0.865994 0.028470 0.050142 0.997206 -0.047496\n4031 3.545726 -0.094237 -1.468480 0.866018 0.029014 0.050059 0.997194 -0.047508\n4032 3.554622 -0.094149 -1.468307 0.866051 0.029585 0.049635 0.997193 -0.047610\n4033 3.563288 -0.094251 -1.468378 0.866005 0.028790 0.050089 0.997200 -0.047473\n4034 3.571558 -0.093751 -1.468771 0.865934 0.031596 0.049381 0.997154 -0.047395\n4035 3.579390 -0.094262 -1.468361 0.865998 0.028664 0.050120 0.997203 -0.047472\n4036 3.588132 -0.094202 -1.468714 0.866053 0.029123 0.049813 0.997197 -0.047635\n4037 3.596697 -0.094075 -1.468153 0.866012 0.029975 0.050004 0.997152 -0.047851\n4038 3.604728 -0.094072 -1.468820 0.866051 0.030839 0.048903 0.997195 -0.047533\n4039 3.612406 -0.094276 -1.468364 0.865976 0.028293 0.050201 0.997210 -0.047450\n4040 3.621112 -0.093973 -1.468393 0.866061 0.030583 0.049050 0.997202 -0.047412\n4041 3.630680 -0.093821 -1.468618 0.866059 0.031410 0.049094 0.997194 -0.046982\n4042 3.637707 -0.093951 -1.468412 0.866021 0.030594 0.049865 0.997149 -0.047660\n4043 3.646817 -0.093999 -1.469137 0.866101 0.029975 0.050122 0.997158 -0.047595\n4044 3.654408 -0.094061 -1.469162 0.866084 0.029754 0.050100 0.997167 -0.047562\n4045 3.662387 -0.094011 -1.469172 0.866101 0.029976 0.050085 0.997161 -0.047565\n4046 3.671423 -0.094172 -1.468794 0.866066 0.029463 0.049670 0.997194 -0.047636\n4047 3.679931 -0.093868 -1.469173 0.866083 0.031145 0.048991 0.997194 -0.047273\n4048 3.687593 -0.094248 -1.468374 0.865995 0.028774 0.050103 0.997200 -0.047477\n4049 3.697219 -0.094279 -1.468395 0.865984 0.028365 0.050162 0.997212 -0.047417\n4050 3.704488 -0.093988 -1.468268 0.866022 0.030437 0.049722 0.997159 -0.047690\n4051 3.712114 -0.094263 -1.468355 0.865993 0.028588 0.050130 0.997204 -0.047477\n4052 3.721412 -0.093816 -1.468706 0.866025 0.031624 0.048468 0.997194 -0.047488\n4053 3.729457 -0.094227 -1.468336 0.866016 0.029165 0.050015 0.997188 -0.047590\n4054 3.738094 -0.093998 -1.468303 0.866019 0.030328 0.049884 0.997153 -0.047733\n4055 3.746120 -0.094262 -1.468368 0.866002 0.028645 0.050106 0.997203 -0.047483\n4056 3.754878 -0.094232 -1.468420 0.866009 0.028980 0.050049 0.997195 -0.047512\n4057 3.763867 -0.094152 -1.468630 0.866059 0.029945 0.049255 0.997209 -0.047445\n4058 3.770704 -0.093863 -1.468565 0.865999 0.030941 0.049745 0.997150 -0.047542\n4059 3.778733 -0.094084 -1.468656 0.866040 0.029945 0.050007 0.997167 -0.047552\n4060 3.787704 -0.094010 -1.468264 0.866021 0.030320 0.049810 0.997158 -0.047710\n4061 3.796061 -0.094048 -1.468497 0.866076 0.030238 0.049239 0.997198 -0.047507\n4062 3.804627 -0.094137 -1.468255 0.866011 0.029809 0.049988 0.997162 -0.047764\n4063 3.812108 -0.093872 -1.468534 0.865967 0.031127 0.049565 0.997154 -0.047514\n4064 3.822159 -0.094120 -1.468666 0.866087 0.029955 0.049384 0.997196 -0.047577\n4065 3.829643 -0.094199 -1.468712 0.866050 0.029054 0.049807 0.997200 -0.047626\n4066 3.837655 -0.093830 -1.469232 0.866085 0.031063 0.049160 0.997194 -0.047149\n4067 3.847202 -0.093975 -1.468277 0.866006 0.030395 0.049894 0.997150 -0.047738\n4068 3.854583 -0.094199 -1.468460 0.866016 0.029494 0.050045 0.997176 -0.047609\n4069 3.862161 -0.094069 -1.468644 0.866071 0.030279 0.049160 0.997201 -0.047502\n4070 3.871597 -0.094198 -1.468723 0.866056 0.029229 0.049795 0.997194 -0.047638\n4071 3.879609 -0.094081 -1.468830 0.866081 0.030337 0.049250 0.997191 -0.047578\n4072 3.887954 -0.093996 -1.468335 0.866024 0.030401 0.049850 0.997152 -0.047728\n4073 3.896114 -0.094094 -1.469066 0.866200 0.030246 0.049811 0.997179 -0.047303\n4074 3.904829 -0.093877 -1.468560 0.866041 0.031366 0.048593 0.997196 -0.047484\n4075 3.913807 -0.093777 -1.468616 0.866022 0.031686 0.048425 0.997196 -0.047447\n4076 3.920770 -0.093925 -1.469090 0.866037 0.031272 0.048828 0.997190 -0.047437\n4077 3.928995 -0.093897 -1.468996 0.865868 0.032067 0.049007 0.997164 -0.047263\n4078 3.937823 -0.094043 -1.469195 0.866081 0.029702 0.050098 0.997169 -0.047556\n4079 3.946221 -0.094200 -1.468655 0.866037 0.029678 0.049435 0.997213 -0.047348\n4080 3.954984 -0.094270 -1.468367 0.865984 0.028463 0.050130 0.997208 -0.047472\n4081 3.962058 -0.094213 -1.468714 0.866038 0.028998 0.049909 0.997196 -0.047624\n4082 3.972056 -0.094162 -1.468673 0.866070 0.029510 0.049605 0.997197 -0.047606\n4083 3.979896 -0.094170 -1.468197 0.866035 0.029432 0.049826 0.997186 -0.047659\n4084 3.987170 -0.094176 -1.468670 0.866059 0.029315 0.049662 0.997200 -0.047616\n4085 3.996707 -0.093873 -1.468620 0.866046 0.031352 0.048616 0.997197 -0.047454\n4086 4.004821 -0.094208 -1.468323 0.866003 0.029267 0.050058 0.997182 -0.047599\n4087 4.012016 -0.094182 -1.468244 0.866005 0.029441 0.050013 0.997176 -0.047673\n4088 4.021808 -0.094217 -1.468284 0.866018 0.028999 0.049979 0.997196 -0.047553\n4089 4.029195 -0.093919 -1.468431 0.866003 0.030759 0.049767 0.997151 -0.047611\n4090 4.038090 -0.094251 -1.468456 0.866017 0.028936 0.050063 0.997195 -0.047517\n4091 4.046254 -0.094019 -1.468646 0.866078 0.030576 0.049107 0.997193 -0.047529\n4092 4.054626 -0.093952 -1.468266 0.866011 0.030819 0.049337 0.997172 -0.047592\n4093 4.063360 -0.094228 -1.468582 0.866016 0.028636 0.050045 0.997200 -0.047622\n4094 4.071419 -0.094113 -1.469357 0.866214 0.030031 0.049645 0.997249 -0.046125\n4095 4.079429 -0.093782 -1.468909 0.865972 0.032106 0.048259 0.997184 -0.047586\n4096 4.087310 -0.093859 -1.468550 0.866040 0.031418 0.048563 0.997197 -0.047473\n4097 4.096204 -0.093877 -1.469155 0.866045 0.031326 0.048813 0.997194 -0.047340\n4098 4.105381 -0.094160 -1.468513 0.866056 0.029639 0.049435 0.997210 -0.047436\n4099 4.113736 -0.094269 -1.468344 0.865987 0.028449 0.050184 0.997205 -0.047489\n4100 4.121237 -0.094073 -1.468641 0.866082 0.030213 0.049242 0.997198 -0.047532\n4101 4.129199 -0.094109 -1.468397 0.866064 0.030105 0.049400 0.997191 -0.047579\n4102 4.136654 -0.093929 -1.468632 0.866066 0.030464 0.049724 0.997171 -0.047437\n4103 4.146836 -0.094236 -1.468349 0.866019 0.028746 0.050001 0.997200 -0.047592\n4104 4.154072 -0.094016 -1.468531 0.866074 0.030411 0.049151 0.997199 -0.047477\n4105 4.162044 -0.094074 -1.468657 0.866077 0.030284 0.049189 0.997197 -0.047548\n4106 4.171464 -0.094230 -1.468399 0.866005 0.029000 0.050035 0.997195 -0.047510\n4107 4.179073 -0.094025 -1.468947 0.866077 0.030689 0.049149 0.997188 -0.047531\n4108 4.187945 -0.094237 -1.468396 0.865999 0.028956 0.050072 0.997195 -0.047509\n4109 4.196782 -0.094042 -1.469259 0.866098 0.029889 0.050099 0.997163 -0.047572\n4110 4.204543 -0.094239 -1.468410 0.866004 0.028910 0.050027 0.997198 -0.047505\n4111 4.213134 -0.094218 -1.468461 0.866010 0.029175 0.050025 0.997190 -0.047531\n4112 4.220158 -0.094011 -1.468687 0.866065 0.030500 0.049002 0.997203 -0.047477\n4113 4.231302 -0.094150 -1.469239 0.866049 0.029198 0.050122 0.997182 -0.047582\n4114 4.237345 -0.093871 -1.468529 0.866041 0.031290 0.048645 0.997198 -0.047450\n4115 4.246007 -0.094207 -1.468703 0.866035 0.028923 0.049957 0.997195 -0.047637\n4116 4.254469 -0.094131 -1.468190 0.866033 0.029757 0.049757 0.997179 -0.047671\n4117 4.263079 -0.093971 -1.468345 0.866049 0.030497 0.049097 0.997201 -0.047435\n4118 4.271324 -0.093535 -1.468680 0.865932 0.032082 0.048090 0.997239 -0.046606\n4119 4.278650 -0.094074 -1.468787 0.866061 0.030519 0.049101 0.997195 -0.047543\n4120 4.286790 -0.094050 -1.469251 0.866094 0.029779 0.050144 0.997163 -0.047597\n4121 4.298037 -0.093961 -1.468308 0.866010 0.030498 0.049780 0.997155 -0.047686\n4122 4.304147 -0.093813 -1.468528 0.866021 0.031565 0.048441 0.997199 -0.047452\n4123 4.314365 -0.094237 -1.468329 0.866008 0.028880 0.050047 0.997196 -0.047558\n4124 4.320624 -0.094065 -1.469225 0.866077 0.029666 0.050107 0.997170 -0.047552\n4125 4.328867 -0.094087 -1.469224 0.866071 0.029553 0.050122 0.997172 -0.047568\n4126 4.336944 -0.093880 -1.468778 0.865901 0.031281 0.049078 0.997203 -0.046896\n4127 4.346358 -0.094225 -1.468254 0.866013 0.028959 0.050049 0.997192 -0.047595\n4128 4.354934 -0.093982 -1.468280 0.866006 0.030497 0.049673 0.997161 -0.047665\n4129 4.361958 -0.094281 -1.468389 0.865976 0.028411 0.050200 0.997208 -0.047433\n4130 4.372951 -0.094195 -1.468728 0.866041 0.029142 0.049863 0.997193 -0.047656\n4131 4.379541 -0.093910 -1.469006 0.866065 0.031086 0.048866 0.997197 -0.047367\n4132 4.388006 -0.094064 -1.469163 0.866069 0.029614 0.050115 0.997171 -0.047562\n4133 4.396452 -0.094253 -1.468372 0.866001 0.028831 0.050065 0.997199 -0.047509\n4134 4.404265 -0.093876 -1.469108 0.865849 0.031728 0.048764 0.997203 -0.046925\n4135 4.412719 -0.094203 -1.468712 0.866040 0.029025 0.049846 0.997198 -0.047637\n4136 4.421359 -0.094178 -1.468655 0.866054 0.029294 0.049727 0.997197 -0.047614\n4137 4.429663 -0.094087 -1.469203 0.866068 0.029542 0.050110 0.997173 -0.047567\n4138 4.438228 -0.094048 -1.468543 0.866078 0.030273 0.049171 0.997201 -0.047502\n4139 4.447209 -0.094050 -1.468660 0.866061 0.030371 0.049047 0.997206 -0.047467\n4140 4.455297 -0.094244 -1.468432 0.866004 0.028901 0.050088 0.997196 -0.047504\n4141 4.463495 -0.093965 -1.468361 0.866023 0.030484 0.049889 0.997148 -0.047732\n4142 4.470320 -0.093796 -1.468762 0.866011 0.031785 0.048413 0.997191 -0.047496\n4143 4.480130 -0.094183 -1.468685 0.866049 0.029153 0.049812 0.997198 -0.047601\n4144 4.487843 -0.094139 -1.468836 0.866073 0.029787 0.049491 0.997194 -0.047623\n4145 4.496878 -0.094164 -1.468360 0.866207 0.030264 0.049234 0.997257 -0.046246\n4146 4.504553 -0.094216 -1.468710 0.866031 0.028931 0.049905 0.997198 -0.047635\n4147 4.512293 -0.094039 -1.468219 0.866030 0.030262 0.049516 0.997178 -0.047629\n4148 4.522074 -0.094163 -1.468629 0.866054 0.029781 0.049396 0.997209 -0.047417\n4149 4.529337 -0.094109 -1.469201 0.866058 0.029371 0.050151 0.997176 -0.047560\n4150 4.538809 -0.094137 -1.468477 0.866026 0.029876 0.050009 0.997163 -0.047665\n4151 4.547299 -0.093971 -1.468554 0.866242 0.031139 0.048799 0.997232 -0.046665\n4152 4.554807 -0.093643 -1.468663 0.865941 0.032205 0.048909 0.997164 -0.047275\n4153 4.564113 -0.094255 -1.468393 0.866000 0.028710 0.050114 0.997200 -0.047498\n4154 4.571502 -0.094262 -1.468342 0.865982 0.028457 0.050180 0.997205 -0.047486\n4155 4.580161 -0.094179 -1.468659 0.866065 0.029396 0.049653 0.997198 -0.047604\n4156 4.587311 -0.094259 -1.468350 0.865984 0.028538 0.050161 0.997203 -0.047486\n4157 4.596950 -0.094144 -1.468777 0.866065 0.029720 0.049582 0.997190 -0.047643\n4158 4.604494 -0.093790 -1.468868 0.866015 0.031716 0.048576 0.997187 -0.047454\n4159 4.613139 -0.094073 -1.469199 0.866190 0.030205 0.049861 0.997178 -0.047304\n4160 4.621327 -0.093859 -1.468870 0.866044 0.030922 0.048804 0.997210 -0.047275\n4161 4.630190 -0.094253 -1.468368 0.865995 0.028759 0.050109 0.997200 -0.047485\n4162 4.638189 -0.094263 -1.468335 0.865979 0.028465 0.050229 0.997202 -0.047494\n4163 4.646864 -0.094269 -1.468361 0.865984 0.028469 0.050128 0.997208 -0.047468\n4164 4.654387 -0.093759 -1.469181 0.866033 0.031213 0.048868 0.997212 -0.046968\n4165 4.661878 -0.094091 -1.469241 0.866069 0.029487 0.050129 0.997174 -0.047565\n4166 4.672371 -0.094214 -1.468312 0.866019 0.029189 0.049987 0.997187 -0.047614\n4167 4.679416 -0.094259 -1.468346 0.865976 0.028466 0.050219 0.997203 -0.047477\n4168 4.687924 -0.094074 -1.468562 0.866076 0.030148 0.049273 0.997198 -0.047527\n4169 4.697781 -0.094197 -1.468820 0.866036 0.028980 0.049876 0.997197 -0.047642\n4170 4.704890 -0.094258 -1.468363 0.865988 0.028671 0.050112 0.997203 -0.047463\n4171 4.712099 -0.094260 -1.468361 0.865981 0.028536 0.050183 0.997204 -0.047459\n4172 4.721581 -0.093892 -1.468361 0.866014 0.031312 0.048761 0.997188 -0.047520\n4173 4.729159 -0.094213 -1.468356 0.866003 0.029164 0.050043 0.997188 -0.047562\n4174 4.738118 -0.093897 -1.468616 0.866044 0.031236 0.048691 0.997196 -0.047475\n4175 4.747739 -0.094061 -1.468651 0.866080 0.030367 0.049194 0.997195 -0.047549\n4176 4.754788 -0.093807 -1.469012 0.866036 0.031069 0.048836 0.997209 -0.047159\n4177 4.763546 -0.094134 -1.468661 0.866076 0.029821 0.049424 0.997198 -0.047592\n4178 4.771576 -0.094252 -1.468367 0.865986 0.028609 0.050123 0.997204 -0.047476\n4179 4.779206 -0.093991 -1.468560 0.866203 0.030780 0.049490 0.997203 -0.046795\n4180 4.789179 -0.093969 -1.469140 0.866077 0.030458 0.049496 0.997180 -0.047480\n4181 4.795777 -0.093806 -1.468760 0.866017 0.031729 0.048496 0.997189 -0.047497\n4182 4.803415 -0.094231 -1.468590 0.866001 0.028584 0.050059 0.997200 -0.047643\n4183 4.812702 -0.094158 -1.469212 0.866046 0.029210 0.050076 0.997185 -0.047563\n4184 4.821056 -0.094240 -1.468421 0.865997 0.028839 0.050094 0.997197 -0.047506\n4185 4.828853 -0.094124 -1.468271 0.866048 0.029596 0.049560 0.997200 -0.047533\n4186 4.839103 -0.093888 -1.468581 0.866040 0.031270 0.048661 0.997196 -0.047478\n4187 4.845622 -0.094187 -1.468650 0.866039 0.029646 0.049464 0.997211 -0.047380\n4188 4.855216 -0.094166 -1.468178 0.866022 0.029543 0.049924 0.997175 -0.047712\n4189 4.862774 -0.093903 -1.468616 0.866046 0.031200 0.048702 0.997197 -0.047470\n4190 4.870230 -0.093907 -1.468223 0.866016 0.030744 0.049016 0.997201 -0.047354\n4191 4.878504 -0.094197 -1.468334 0.865999 0.029305 0.050035 0.997183 -0.047588\n4192 4.887281 -0.093906 -1.468511 0.866124 0.031430 0.049117 0.997221 -0.046358\n4193 4.896684 -0.093715 -1.469326 0.866029 0.031343 0.048837 0.997222 -0.046705\n4194 4.904661 -0.094214 -1.468725 0.866029 0.028954 0.049917 0.997196 -0.047654\n4195 4.912600 -0.094203 -1.468696 0.866026 0.028938 0.049918 0.997198 -0.047619\n4196 4.921420 -0.094263 -1.468352 0.865973 0.028522 0.050200 0.997203 -0.047471\n4197 4.929953 -0.093977 -1.468639 0.866062 0.030838 0.048907 0.997197 -0.047497\n4198 4.938447 -0.093713 -1.469327 0.866032 0.031377 0.048802 0.997223 -0.046690\n4199 4.946484 -0.094134 -1.469227 0.866047 0.029276 0.050159 0.997177 -0.047583\n4200 4.954836 -0.094260 -1.468366 0.865975 0.028506 0.050180 0.997204 -0.047462\n4201 4.962267 -0.094149 -1.468663 0.866035 0.030084 0.049204 0.997212 -0.047356\n4202 4.971459 -0.094269 -1.468399 0.865978 0.028443 0.050179 0.997208 -0.047429\n4203 4.980690 -0.094005 -1.468255 0.866007 0.030254 0.050010 0.997145 -0.047816\n4204 4.988252 -0.094260 -1.468363 0.865986 0.028544 0.050148 0.997204 -0.047488\n4205 4.995276 -0.093872 -1.468585 0.866037 0.031363 0.048625 0.997196 -0.047463\n4206 5.004417 -0.094249 -1.468392 0.865987 0.028651 0.050092 0.997205 -0.047462\n4207 5.012257 -0.094009 -1.468359 0.866028 0.030429 0.049892 0.997150 -0.047722\n4208 5.021940 -0.094020 -1.468401 0.866057 0.030222 0.049227 0.997202 -0.047459\n4209 5.029327 -0.093812 -1.468691 0.866023 0.031588 0.048535 0.997194 -0.047447\n4210 5.036771 -0.094263 -1.468361 0.865979 0.028484 0.050190 0.997205 -0.047455\n4211 5.054778 -0.094094 -1.468668 0.866071 0.030158 0.049242 0.997198 -0.047562\n4212 5.054844 -0.094097 -1.468663 0.866075 0.030110 0.049333 0.997194 -0.047572\n4213 5.063719 -0.094236 -1.468541 0.866008 0.028666 0.050035 0.997201 -0.047602\n4214 5.071017 -0.094262 -1.468367 0.865982 0.028590 0.050197 0.997202 -0.047443\n4215 5.079081 -0.094147 -1.468664 0.866068 0.029636 0.049552 0.997197 -0.047591\n4216 5.086878 -0.093905 -1.468462 0.865990 0.030848 0.049731 0.997151 -0.047601\n4217 5.095795 -0.094263 -1.468364 0.865978 0.028573 0.050155 0.997204 -0.047467\n4218 5.103330 -0.094277 -1.468331 0.865980 0.028372 0.050181 0.997206 -0.047502\n4219 5.113357 -0.094135 -1.468711 0.866203 0.030532 0.049388 0.997215 -0.046801\n4220 5.120977 -0.094167 -1.468271 0.866020 0.029615 0.049871 0.997177 -0.047684\n4221 5.129680 -0.093483 -1.468800 0.865702 0.031746 0.046818 0.997356 -0.045616\n4222 5.137563 -0.093774 -1.468518 0.866009 0.031657 0.048382 0.997199 -0.047443\n4223 5.145292 -0.093929 -1.468361 0.866043 0.030713 0.048980 0.997203 -0.047374\n4224 5.155390 -0.094049 -1.469249 0.866083 0.029773 0.050158 0.997162 -0.047591\n4225 5.163012 -0.094037 -1.469309 0.866186 0.030199 0.049437 0.997264 -0.045929\n4226 5.171273 -0.094059 -1.468299 0.866034 0.030277 0.049423 0.997184 -0.047600\n4227 5.179915 -0.094152 -1.468663 0.866068 0.029638 0.049572 0.997195 -0.047605\n4228 5.188243 -0.094149 -1.469200 0.866042 0.029158 0.050140 0.997183 -0.047560\n4229 5.195030 -0.093888 -1.468748 0.865903 0.031234 0.049121 0.997199 -0.046967\n4230 5.203975 -0.093811 -1.468654 0.866014 0.031656 0.048433 0.997194 -0.047489\n4231 5.213523 -0.094270 -1.468353 0.865978 0.028507 0.050169 0.997204 -0.047493\n4232 5.221493 -0.094041 -1.469109 0.866081 0.029922 0.050099 0.997162 -0.047569\n4233 5.229795 -0.093889 -1.468582 0.866034 0.031271 0.048626 0.997198 -0.047472\n4234 5.237979 -0.094043 -1.468270 0.866029 0.030321 0.049479 0.997179 -0.047608\n4235 5.245213 -0.093802 -1.468715 0.866007 0.031732 0.048434 0.997192 -0.047495\n4236 5.254041 -0.093960 -1.468972 0.866012 0.031600 0.049030 0.997180 -0.047210\n4237 5.263288 -0.094173 -1.468659 0.866051 0.029386 0.049716 0.997195 -0.047621\n4238 5.271356 -0.094129 -1.468543 0.866043 0.029977 0.049289 0.997209 -0.047404\n4239 5.278761 -0.093970 -1.468656 0.866059 0.030880 0.048879 0.997197 -0.047486\n4240 5.288057 -0.094118 -1.468629 0.866057 0.030050 0.049255 0.997205 -0.047476\n4241 5.296103 -0.094236 -1.468398 0.865992 0.028953 0.050089 0.997194 -0.047514\n4242 5.303296 -0.093946 -1.468481 0.866053 0.030791 0.048936 0.997200 -0.047423\n4243 5.312493 -0.094131 -1.468814 0.866060 0.029660 0.049569 0.997193 -0.047633\n4244 5.320417 -0.094215 -1.468302 0.866002 0.029206 0.050011 0.997185 -0.047622\n4245 5.328852 -0.094123 -1.469018 0.866198 0.030390 0.049720 0.997186 -0.047162\n4246 5.336814 -0.094162 -1.468657 0.866062 0.029571 0.049560 0.997199 -0.047587\n4247 5.347631 -0.094094 -1.468298 0.866036 0.030109 0.049483 0.997185 -0.047611\n4248 5.355298 -0.094261 -1.468356 0.865987 0.028599 0.050144 0.997200 -0.047532\n4249 5.363574 -0.094264 -1.468370 0.865977 0.028533 0.050118 0.997207 -0.047465\n4250 5.371514 -0.094263 -1.468363 0.865981 0.028560 0.050148 0.997203 -0.047503\n4251 5.378458 -0.094036 -1.468994 0.866030 0.031129 0.049039 0.997213 -0.046832\n4252 5.388018 -0.094042 -1.468256 0.866035 0.030083 0.049375 0.997197 -0.047491\n4253 5.396867 -0.094141 -1.468667 0.866036 0.030213 0.049134 0.997212 -0.047336\n4254 5.404413 -0.094034 -1.468844 0.866023 0.031080 0.048827 0.997189 -0.047590\n4255 5.412898 -0.094287 -1.468326 0.865969 0.028202 0.050227 0.997209 -0.047506\n4256 5.419983 -0.093867 -1.469076 0.865844 0.031580 0.048776 0.997212 -0.046813\n4257 5.430107 -0.094240 -1.468460 0.866002 0.028979 0.050106 0.997192 -0.047509\n4258 5.438282 -0.094183 -1.468366 0.866034 0.029277 0.049826 0.997193 -0.047607\n4259 5.445426 -0.094260 -1.468364 0.865977 0.028582 0.050171 0.997203 -0.047465\n4260 5.453256 -0.094041 -1.468658 0.866067 0.030486 0.049136 0.997194 -0.047537\n4261 5.464555 -0.094090 -1.469196 0.866182 0.030279 0.049744 0.997185 -0.047238\n4262 5.470643 -0.094007 -1.469027 0.866070 0.030315 0.049404 0.997186 -0.047539\n4263 5.480048 -0.093800 -1.468956 0.866025 0.031085 0.048766 0.997213 -0.047143\n4264 5.488233 -0.093881 -1.468757 0.865897 0.031252 0.049118 0.997201 -0.046912\n4265 5.495069 -0.094261 -1.468348 0.865972 0.028427 0.050188 0.997205 -0.047497\n4266 5.505414 -0.093769 -1.468807 0.865890 0.031742 0.049411 0.997144 -0.047490\n4267 5.512972 -0.093784 -1.468734 0.866006 0.031784 0.048424 0.997191 -0.047490\n4268 5.520399 -0.094009 -1.468701 0.866060 0.030549 0.049037 0.997200 -0.047475\n4269 5.528588 -0.094254 -1.468368 0.865996 0.028667 0.050120 0.997200 -0.047532\n4270 5.537564 -0.094261 -1.468368 0.865987 0.028638 0.050103 0.997204 -0.047485\n4271 5.545766 -0.094220 -1.468428 0.866002 0.028829 0.050028 0.997198 -0.047570\n4272 5.554606 -0.094202 -1.468657 0.866037 0.029111 0.049823 0.997197 -0.047626\n4273 5.563099 -0.094240 -1.468450 0.866004 0.028946 0.050064 0.997195 -0.047527\n4274 5.573176 -0.094072 -1.468660 0.866056 0.030267 0.049173 0.997201 -0.047509\n4275 5.579958 -0.094011 -1.468277 0.866000 0.030464 0.049696 0.997161 -0.047672\n4276 5.588052 -0.094250 -1.468386 0.865983 0.028788 0.050117 0.997198 -0.047490\n4277 5.596033 -0.094140 -1.468813 0.866062 0.029760 0.049588 0.997189 -0.047641\n4278 5.603192 -0.093811 -1.468663 0.866010 0.031627 0.048518 0.997191 -0.047490\n4279 5.611418 -0.094272 -1.468365 0.865974 0.028510 0.050178 0.997204 -0.047464\n4280 5.620734 -0.093552 -1.468522 0.865914 0.032148 0.048422 0.997197 -0.047108\n4281 5.630047 -0.093897 -1.468764 0.865895 0.031256 0.049110 0.997201 -0.046919\n4282 5.637454 -0.094176 -1.468388 0.866000 0.029556 0.050043 0.997172 -0.047644\n4283 5.644975 -0.094275 -1.468369 0.865980 0.028472 0.050193 0.997205 -0.047456\n4284 5.655273 -0.093916 -1.468415 0.865997 0.030715 0.049812 0.997150 -0.047627\n4285 5.662264 -0.094172 -1.468636 0.866040 0.029781 0.049402 0.997209 -0.047408\n4286 5.669899 -0.094221 -1.468717 0.866018 0.028838 0.049961 0.997197 -0.047646\n4287 5.678271 -0.094199 -1.468731 0.866027 0.029080 0.049878 0.997194 -0.047648\n4288 5.687188 -0.093817 -1.468700 0.865964 0.032014 0.048237 0.997186 -0.047631\n4289 5.695747 -0.094255 -1.468369 0.865980 0.028623 0.050134 0.997203 -0.047470\n4290 5.704572 -0.094036 -1.468649 0.866067 0.030590 0.049113 0.997193 -0.047523\n4291 5.712594 -0.093998 -1.468276 0.865997 0.030410 0.049726 0.997162 -0.047652\n4292 5.721132 -0.094085 -1.468112 0.865993 0.029927 0.050001 0.997154 -0.047843\n4293 5.728294 -0.094038 -1.468938 0.866066 0.030377 0.049309 0.997189 -0.047547\n4294 5.737219 -0.094279 -1.468343 0.865969 0.028379 0.050200 0.997205 -0.047498\n4295 5.746745 -0.093803 -1.468728 0.866009 0.031700 0.048468 0.997191 -0.047505\n4296 5.754917 -0.093927 -1.468438 0.866003 0.030695 0.049841 0.997149 -0.047628\n4297 5.762205 -0.094107 -1.468670 0.866071 0.030071 0.049381 0.997192 -0.047589\n4298 5.771340 -0.094215 -1.468443 0.866012 0.028919 0.049952 0.997198 -0.047598\n4299 5.779852 -0.094171 -1.468513 0.866010 0.029613 0.050057 0.997172 -0.047597\n4300 5.786479 -0.094180 -1.468241 0.866000 0.029481 0.050003 0.997174 -0.047685\n4301 5.797979 -0.094005 -1.468930 0.866054 0.030947 0.049006 0.997187 -0.047521\n4302 5.804304 -0.094036 -1.468252 0.866005 0.030284 0.049723 0.997164 -0.047692\n4303 5.812042 -0.094148 -1.468676 0.866058 0.029764 0.049525 0.997194 -0.047600\n4304 5.820766 -0.094109 -1.469206 0.866051 0.029500 0.050110 0.997174 -0.047572\n4305 5.828757 -0.094143 -1.469245 0.866047 0.029257 0.050091 0.997183 -0.047553\n4306 5.837764 -0.093941 -1.469037 0.866043 0.031159 0.048878 0.997190 -0.047455\n4307 5.847014 -0.094163 -1.468155 0.866006 0.029609 0.049892 0.997174 -0.047723\n4308 5.854650 -0.093952 -1.468297 0.866032 0.030585 0.049106 0.997197 -0.047442\n4309 5.862279 -0.093858 -1.468533 0.866021 0.031383 0.048566 0.997197 -0.047482\n4310 5.870697 -0.094103 -1.468664 0.866070 0.030042 0.049374 0.997194 -0.047578\n4311 5.880006 -0.094054 -1.469008 0.866066 0.030117 0.049527 0.997184 -0.047576\n4312 5.887757 -0.093642 -1.468827 0.865755 0.032281 0.048674 0.997164 -0.047471\n4313 5.896129 -0.094252 -1.468398 0.865990 0.028728 0.050114 0.997199 -0.047511\n4314 5.904633 -0.093940 -1.468592 0.866044 0.031023 0.048848 0.997194 -0.047492\n4315 5.913135 -0.093871 -1.468610 0.866026 0.031328 0.048640 0.997196 -0.047458\n4316 5.920129 -0.094001 -1.468337 0.866015 0.030499 0.049826 0.997154 -0.047667\n4317 5.928780 -0.093930 -1.469007 0.866040 0.031123 0.048948 0.997187 -0.047464\n4318 5.937139 -0.094254 -1.468373 0.865979 0.028733 0.050142 0.997199 -0.047483\n4319 5.945222 -0.094260 -1.468381 0.865985 0.028710 0.050081 0.997202 -0.047492\n4320 5.955613 -0.094288 -1.468393 0.865969 0.028413 0.050145 0.997210 -0.047443\n4321 5.963096 -0.093808 -1.468638 0.866011 0.031634 0.048466 0.997194 -0.047491\n4322 5.971264 -0.094135 -1.469176 0.866040 0.029311 0.050127 0.997179 -0.047567\n4323 5.980491 -0.093860 -1.468782 0.865875 0.031325 0.049069 0.997204 -0.046861\n4324 5.987981 -0.093969 -1.468344 0.866001 0.030510 0.049840 0.997151 -0.047690\n4325 5.997285 -0.094173 -1.468659 0.866027 0.029838 0.049335 0.997213 -0.047340\n4326 6.004149 -0.094129 -1.468605 0.866065 0.029646 0.049473 0.997203 -0.047548\n4327 6.013709 -0.094034 -1.468648 0.866071 0.030502 0.049130 0.997194 -0.047535\n4328 6.021317 -0.094237 -1.468442 0.865994 0.028911 0.050078 0.997195 -0.047515\n4329 6.030199 -0.094263 -1.468397 0.865990 0.028733 0.050102 0.997200 -0.047504\n4330 6.037925 -0.094193 -1.468207 0.865987 0.029216 0.050011 0.997185 -0.047629\n4331 6.045401 -0.094255 -1.468411 0.865990 0.028806 0.050069 0.997199 -0.047505\n4332 6.054591 -0.093995 -1.468729 0.866179 0.031250 0.048780 0.997223 -0.046803\n4333 6.063262 -0.094170 -1.468228 0.865987 0.029509 0.050059 0.997170 -0.047706\n4334 6.071423 -0.094169 -1.468529 0.866041 0.029263 0.049720 0.997200 -0.047571\n4335 6.078293 -0.094040 -1.468637 0.866068 0.030523 0.049181 0.997192 -0.047526\n4336 6.086500 -0.093833 -1.468598 0.866014 0.031498 0.048518 0.997195 -0.047500\n4337 6.097913 -0.093929 -1.468573 0.866042 0.031030 0.048805 0.997196 -0.047484\n4338 6.104664 -0.094228 -1.468411 0.865991 0.029005 0.050113 0.997190 -0.047528\n4339 6.113423 -0.094255 -1.468371 0.865973 0.028620 0.050176 0.997202 -0.047453\n4340 6.121371 -0.094282 -1.468327 0.865955 0.028201 0.050314 0.997204 -0.047515\n4341 6.129018 -0.094281 -1.468362 0.865965 0.028297 0.050249 0.997207 -0.047452\n4342 6.139419 -0.094007 -1.468207 0.865993 0.030245 0.049945 0.997149 -0.047799\n4343 6.146022 -0.094014 -1.469152 0.866078 0.029962 0.050131 0.997159 -0.047572\n4344 6.153378 -0.094187 -1.468736 0.866040 0.029296 0.049780 0.997194 -0.047631\n4345 6.162066 -0.094159 -1.468638 0.866040 0.029824 0.049360 0.997209 -0.047407\n4346 6.172092 -0.094042 -1.468240 0.866002 0.030294 0.049612 0.997172 -0.047642\n4347 6.179363 -0.093854 -1.468426 0.866017 0.031213 0.048731 0.997197 -0.047420\n4348 6.187862 -0.094026 -1.468741 0.866021 0.031052 0.048780 0.997193 -0.047557\n4349 6.195007 -0.094123 -1.468377 0.866046 0.029873 0.049528 0.997191 -0.047597\n4350 6.204204 -0.093819 -1.468782 0.866003 0.031659 0.048531 0.997190 -0.047491\n4351 6.213461 -0.093977 -1.468315 0.865987 0.030553 0.049730 0.997157 -0.047659\n4352 6.221931 -0.093877 -1.469091 0.865831 0.031624 0.048780 0.997210 -0.046824\n4353 6.230090 -0.094085 -1.468616 0.866067 0.030151 0.049298 0.997197 -0.047537\n4354 6.236786 -0.094041 -1.468143 0.866018 0.030010 0.049429 0.997194 -0.047533\n4355 6.248255 -0.093834 -1.468571 0.866011 0.031591 0.048500 0.997194 -0.047485\n4356 6.253698 -0.094087 -1.468647 0.866065 0.030121 0.049293 0.997196 -0.047568\n4357 6.263229 -0.094204 -1.468678 0.866028 0.029046 0.049905 0.997196 -0.047600\n4358 6.271377 -0.094195 -1.468228 0.866017 0.029206 0.049977 0.997186 -0.047649\n4359 6.279544 -0.094044 -1.468649 0.866052 0.030445 0.049053 0.997204 -0.047440\n4360 6.287814 -0.094239 -1.468381 0.865983 0.028894 0.050101 0.997195 -0.047502\n4361 6.296005 -0.094249 -1.468430 0.865987 0.028819 0.050136 0.997196 -0.047506\n4362 6.304253 -0.094232 -1.468344 0.865993 0.028993 0.050057 0.997192 -0.047555\n4363 6.312402 -0.094247 -1.468376 0.865981 0.028645 0.050146 0.997200 -0.047510\n4364 6.319969 -0.094176 -1.468655 0.866053 0.029404 0.049679 0.997196 -0.047623\n4365 6.330141 -0.094155 -1.468663 0.866058 0.029600 0.049538 0.997198 -0.047599\n4366 6.338326 -0.093936 -1.468300 0.866017 0.030712 0.049019 0.997199 -0.047407\n4367 6.345246 -0.094042 -1.468237 0.866005 0.030330 0.049902 0.997148 -0.047803\n4368 6.354179 -0.094215 -1.468660 0.866030 0.029040 0.049800 0.997200 -0.047637\n4369 6.361812 -0.093846 -1.468406 0.866012 0.031288 0.048639 0.997198 -0.047450\n4370 6.372075 -0.093989 -1.468730 0.866051 0.030564 0.049010 0.997202 -0.047467\n4371 6.378984 -0.094177 -1.468665 0.866029 0.029770 0.049347 0.997216 -0.047326\n4372 6.387874 -0.094194 -1.468703 0.866043 0.029253 0.049813 0.997193 -0.047640\n4373 6.395000 -0.094278 -1.468375 0.865962 0.028366 0.050245 0.997205 -0.047456\n4374 6.404117 -0.094147 -1.468253 0.866025 0.029681 0.049774 0.997181 -0.047668\n4375 6.413716 -0.094191 -1.468662 0.866029 0.029665 0.049450 0.997213 -0.047333\n4376 6.421294 -0.094274 -1.468305 0.865963 0.028218 0.050261 0.997205 -0.047527\n4377 6.430035 -0.094203 -1.468718 0.866029 0.029072 0.049875 0.997195 -0.047642\n4378 6.437984 -0.094273 -1.468371 0.865966 0.028456 0.050149 0.997207 -0.047472\n4379 6.445375 -0.094126 -1.468843 0.866057 0.029838 0.049542 0.997189 -0.047634\n4380 6.453904 -0.094073 -1.468660 0.866045 0.030211 0.049189 0.997202 -0.047495\n4381 6.464147 -0.094228 -1.468404 0.865983 0.029020 0.050097 0.997191 -0.047521\n4382 6.471400 -0.093943 -1.468315 0.866023 0.030596 0.049084 0.997200 -0.047397\n4383 6.479121 -0.093623 -1.469140 0.865958 0.031256 0.047986 0.997306 -0.045837\n4384 6.488029 -0.094070 -1.468257 0.866029 0.029944 0.049424 0.997198 -0.047502\n4385 6.496610 -0.094212 -1.468416 0.866005 0.029210 0.050031 0.997186 -0.047571\n4386 6.504375 -0.094277 -1.468391 0.865965 0.028424 0.050185 0.997207 -0.047446\n4387 6.513406 -0.094249 -1.468372 0.865978 0.028743 0.050147 0.997199 -0.047472\n4388 6.521005 -0.094071 -1.468663 0.866067 0.030309 0.049225 0.997194 -0.047562\n4389 6.528876 -0.094218 -1.468354 0.866011 0.028947 0.049956 0.997196 -0.047609\n4390 6.538539 -0.094089 -1.469180 0.866049 0.029615 0.050112 0.997171 -0.047564\n4391 6.546716 -0.094003 -1.468654 0.866057 0.030705 0.049012 0.997195 -0.047502\n4392 6.553322 -0.094013 -1.468691 0.866048 0.030506 0.049025 0.997202 -0.047472\n4393 6.562071 -0.094243 -1.468412 0.865986 0.028804 0.050094 0.997199 -0.047498\n4394 6.570983 -0.094185 -1.468668 0.866044 0.029427 0.049697 0.997194 -0.047629\n4395 6.579809 -0.094258 -1.468362 0.865974 0.028600 0.050148 0.997201 -0.047520\n4396 6.587563 -0.094198 -1.468451 0.865996 0.029407 0.050065 0.997178 -0.047588\n4397 6.595379 -0.094260 -1.468376 0.865966 0.028585 0.050162 0.997203 -0.047459\n4398 6.603373 -0.093924 -1.468400 0.865972 0.030792 0.049693 0.997155 -0.047591\n4399 6.614203 -0.094224 -1.468370 0.865990 0.029093 0.050062 0.997188 -0.047570\n4400 6.620818 -0.094080 -1.468332 0.866032 0.030228 0.049414 0.997186 -0.047594\n4401 6.629844 -0.094264 -1.468347 0.865952 0.028426 0.050271 0.997201 -0.047494\n4402 6.637529 -0.093980 -1.468730 0.866042 0.030594 0.048990 0.997202 -0.047458\n4403 6.645302 -0.094167 -1.468654 0.866027 0.029895 0.049353 0.997209 -0.047388\n4404 6.655385 -0.093966 -1.468342 0.866031 0.030545 0.049085 0.997200 -0.047425\n4405 6.663035 -0.093940 -1.468665 0.866023 0.031096 0.048745 0.997200 -0.047419\n4406 6.670020 -0.094056 -1.468667 0.866007 0.030721 0.048903 0.997205 -0.047411\n4407 6.678672 -0.094215 -1.468332 0.865989 0.029178 0.050072 0.997185 -0.047579\n4408 6.687418 -0.093922 -1.468550 0.866039 0.030986 0.048816 0.997200 -0.047435\n4409 6.695213 -0.094140 -1.468555 0.866047 0.029577 0.049584 0.997199 -0.047549\n4410 6.703402 -0.094223 -1.468247 0.865996 0.029032 0.050005 0.997190 -0.047629\n4411 6.712390 -0.094260 -1.468366 0.865973 0.028669 0.050150 0.997200 -0.047496\n4412 6.721668 -0.093906 -1.468579 0.866028 0.031195 0.048729 0.997195 -0.047480\n4413 6.729737 -0.094251 -1.468378 0.865972 0.028678 0.050107 0.997202 -0.047483\n4414 6.738038 -0.094017 -1.469183 0.866076 0.029939 0.050125 0.997160 -0.047571\n4415 6.745335 -0.094112 -1.468835 0.866056 0.029879 0.049496 0.997191 -0.047613\n4416 6.754573 -0.093878 -1.468606 0.866028 0.031322 0.048669 0.997195 -0.047462\n4417 6.763402 -0.093941 -1.469040 0.866051 0.030939 0.049141 0.997183 -0.047469\n4418 6.771101 -0.094281 -1.468338 0.865969 0.028396 0.050207 0.997204 -0.047512\n4419 6.778469 -0.093717 -1.468706 0.865901 0.031879 0.049164 0.997154 -0.047451\n4420 6.788040 -0.093439 -1.468776 0.865725 0.031945 0.046938 0.997333 -0.045869\n4421 6.796585 -0.094249 -1.468385 0.865983 0.028822 0.050079 0.997198 -0.047510\n4422 6.804210 -0.093900 -1.468785 0.865886 0.031263 0.049078 0.997204 -0.046885\n4423 6.813056 -0.094048 -1.469049 0.866063 0.030226 0.049502 0.997183 -0.047567\n4424 6.821246 -0.094163 -1.469245 0.866034 0.029254 0.050125 0.997181 -0.047569\n4425 6.828885 -0.094189 -1.468655 0.866033 0.029165 0.049775 0.997199 -0.047609\n4426 6.838504 -0.094060 -1.468657 0.866050 0.030261 0.049192 0.997200 -0.047508\n4427 6.846293 -0.094241 -1.468474 0.865994 0.029030 0.050050 0.997193 -0.047519\n4428 6.854308 -0.094050 -1.469143 0.866173 0.030251 0.049904 0.997171 -0.047369\n4429 6.861548 -0.094284 -1.468378 0.865955 0.028363 0.050236 0.997206 -0.047460\n4430 6.870764 -0.094263 -1.468373 0.865967 0.028549 0.050177 0.997203 -0.047479\n4431 6.879762 -0.094171 -1.468542 0.866027 0.029600 0.049510 0.997207 -0.047448\n4432 6.888319 -0.094055 -1.468889 0.866058 0.030345 0.049332 0.997187 -0.047582\n4433 6.895768 -0.094169 -1.468796 0.866042 0.029456 0.049732 0.997190 -0.047665\n4434 6.903232 -0.094015 -1.468228 0.866003 0.030320 0.049733 0.997162 -0.047699\n4435 6.913479 -0.094152 -1.469199 0.866033 0.029170 0.050156 0.997181 -0.047567\n4436 6.921030 -0.093918 -1.468616 0.866037 0.031110 0.048766 0.997196 -0.047482\n4437 6.929659 -0.094248 -1.468402 0.865983 0.028815 0.050124 0.997196 -0.047509\n4438 6.937350 -0.094273 -1.468380 0.865959 0.028448 0.050212 0.997205 -0.047454\n4439 6.945195 -0.094236 -1.468525 0.865989 0.028611 0.050048 0.997201 -0.047607\n4440 6.955471 -0.094135 -1.468258 0.866003 0.029840 0.049980 0.997162 -0.047754\n4441 6.962907 -0.094140 -1.468293 0.866029 0.029643 0.049736 0.997185 -0.047636\n4442 6.971289 -0.094166 -1.468667 0.866044 0.029496 0.049616 0.997197 -0.047600\n4443 6.979852 -0.094067 -1.468920 0.866058 0.030112 0.049474 0.997187 -0.047588\n4444 6.988604 -0.093979 -1.468642 0.866047 0.030881 0.048932 0.997194 -0.047505\n4445 6.996852 -0.094143 -1.468667 0.866044 0.029630 0.049613 0.997194 -0.047595\n4446 7.004312 -0.094265 -1.468379 0.865975 0.028633 0.050157 0.997202 -0.047473\n4447 7.013126 -0.094072 -1.468666 0.866058 0.030253 0.049244 0.997195 -0.047563\n4448 7.021282 -0.094258 -1.468374 0.865974 0.028672 0.050159 0.997200 -0.047488\n4449 7.029855 -0.094262 -1.468372 0.865968 0.028637 0.050180 0.997201 -0.047468\n4450 7.038532 -0.094269 -1.468381 0.865963 0.028450 0.050199 0.997205 -0.047462\n4451 7.047111 -0.094215 -1.468413 0.865999 0.029209 0.050052 0.997185 -0.047580\n4452 7.053121 -0.094227 -1.468271 0.865991 0.028934 0.050046 0.997193 -0.047593\n4453 7.063272 -0.093956 -1.468612 0.866041 0.030985 0.048908 0.997192 -0.047492\n4454 7.071391 -0.094189 -1.468742 0.866027 0.029200 0.049854 0.997192 -0.047639\n4455 7.079766 -0.094263 -1.468368 0.865973 0.028607 0.050140 0.997202 -0.047497\n4456 7.087758 -0.093886 -1.468798 0.865873 0.031288 0.049089 0.997202 -0.046900\n4457 7.094719 -0.094258 -1.468378 0.865972 0.028698 0.050125 0.997201 -0.047476\n4458 7.105246 -0.094225 -1.468554 0.865997 0.028765 0.049976 0.997200 -0.047608\n4459 7.112575 -0.094180 -1.468667 0.866034 0.029340 0.049709 0.997197 -0.047614\n4460 7.121916 -0.093848 -1.468650 0.866017 0.031437 0.048629 0.997193 -0.047471\n4461 7.129538 -0.094222 -1.468347 0.865982 0.029190 0.050068 0.997185 -0.047567\n4462 7.137703 -0.093855 -1.468602 0.866016 0.031374 0.048620 0.997195 -0.047469\n4463 7.146301 -0.093774 -1.469023 0.866016 0.031262 0.048820 0.997205 -0.047134\n4464 7.153763 -0.094208 -1.468737 0.866020 0.029043 0.049913 0.997194 -0.047646\n4465 7.162390 -0.094033 -1.468663 0.866060 0.030521 0.049106 0.997195 -0.047534\n4466 7.170625 -0.094155 -1.468874 0.866189 0.030301 0.049721 0.997191 -0.047107\n4467 7.178600 -0.094275 -1.468362 0.865960 0.028370 0.050233 0.997205 -0.047467\n4468 7.188044 -0.094001 -1.468963 0.865973 0.031145 0.048973 0.997224 -0.046645\n4469 7.196746 -0.094190 -1.469234 0.866018 0.028999 0.050154 0.997186 -0.047578\n4470 7.204448 -0.094236 -1.468492 0.865991 0.028743 0.050020 0.997200 -0.047584\n4471 7.211925 -0.094273 -1.468355 0.865953 0.028362 0.050219 0.997206 -0.047464\n4472 7.220748 -0.094237 -1.468397 0.865979 0.028999 0.050086 0.997192 -0.047521\n4473 7.230163 -0.094137 -1.468958 0.866178 0.030278 0.049752 0.997187 -0.047190\n4474 7.237937 -0.093934 -1.468625 0.866035 0.031044 0.048822 0.997195 -0.047482\n4475 7.244954 -0.094010 -1.468648 0.866051 0.030695 0.049037 0.997194 -0.047514\n4476 7.253402 -0.094234 -1.468428 0.865995 0.028710 0.050013 0.997200 -0.047600\n4477 7.263735 -0.094195 -1.468739 0.866019 0.029141 0.049899 0.997191 -0.047646\n4478 7.271023 -0.094110 -1.469034 0.866171 0.030338 0.049796 0.997180 -0.047235\n4479 7.280215 -0.094229 -1.468311 0.865982 0.029022 0.050102 0.997188 -0.047569\n4480 7.287540 -0.094149 -1.469247 0.866025 0.029176 0.050128 0.997183 -0.047570\n4481 7.295065 -0.094069 -1.468759 0.866015 0.030879 0.048887 0.997193 -0.047564\n4482 7.304474 -0.094168 -1.468425 0.865985 0.029567 0.050106 0.997168 -0.047654\n4483 7.312360 -0.094220 -1.468701 0.866007 0.028849 0.049959 0.997197 -0.047638\n4484 7.319860 -0.094186 -1.468400 0.865999 0.029435 0.050019 0.997178 -0.047625\n4485 7.328282 -0.094097 -1.468544 0.866052 0.029909 0.049429 0.997198 -0.047525\n4486 7.337856 -0.094159 -1.468672 0.866044 0.029536 0.049589 0.997198 -0.047592\n4487 7.346013 -0.094276 -1.468359 0.865957 0.028345 0.050232 0.997206 -0.047479\n4488 7.354481 -0.094139 -1.468934 0.866165 0.030342 0.049678 0.997192 -0.047113\n4489 7.363023 -0.094233 -1.468407 0.865981 0.029019 0.050069 0.997192 -0.047524\n4490 7.371962 -0.094215 -1.468351 0.865988 0.029150 0.050060 0.997187 -0.047566\n4491 7.380581 -0.094212 -1.468351 0.865981 0.029233 0.050047 0.997184 -0.047582\n4492 7.388016 -0.094280 -1.468364 0.865951 0.028312 0.050214 0.997208 -0.047476\n4493 7.396856 -0.093832 -1.468751 0.866004 0.031572 0.048581 0.997190 -0.047487\n4494 7.404111 -0.094006 -1.468306 0.865992 0.030383 0.049887 0.997151 -0.047724\n4495 7.415934 -0.093636 -1.468644 0.865900 0.031961 0.048702 0.997189 -0.047121\n4496 7.420772 -0.093821 -1.468713 0.866013 0.031517 0.048566 0.997194 -0.047448\n4497 7.428490 -0.094263 -1.468391 0.865976 0.028659 0.050117 0.997201 -0.047502\n4498 7.438685 -0.094046 -1.469211 0.866059 0.029795 0.050135 0.997163 -0.047595\n4499 7.446402 -0.093774 -1.468841 0.865984 0.031847 0.048435 0.997188 -0.047505\n4500 7.453423 -0.094258 -1.468370 0.865961 0.028593 0.050219 0.997200 -0.047453\n4501 7.461738 -0.094221 -1.468362 0.865987 0.029108 0.050075 0.997188 -0.047553\n4502 7.470292 -0.093859 -1.468639 0.866016 0.031348 0.048619 0.997196 -0.047469\n4503 7.478289 -0.094094 -1.469235 0.866049 0.029583 0.050130 0.997171 -0.047565\n4504 7.487703 -0.094172 -1.468240 0.865993 0.029490 0.049995 0.997174 -0.047692\n4505 7.496052 -0.094078 -1.468662 0.866057 0.030284 0.049280 0.997192 -0.047566\n4506 7.503246 -0.093800 -1.468859 0.866008 0.031125 0.048689 0.997214 -0.047173\n4507 7.513515 -0.093870 -1.469046 0.866011 0.031354 0.048694 0.997198 -0.047341\n4508 7.520609 -0.094210 -1.468272 0.866002 0.029123 0.050019 0.997187 -0.047634\n4509 7.528721 -0.094050 -1.468244 0.865994 0.030274 0.049658 0.997168 -0.047683\n4510 7.538019 -0.094229 -1.468581 0.865983 0.028671 0.050040 0.997199 -0.047628\n4511 7.546708 -0.093815 -1.468624 0.865996 0.031595 0.048444 0.997195 -0.047502\n4512 7.554343 -0.094112 -1.468670 0.866051 0.029941 0.049421 0.997195 -0.047572\n4513 7.561600 -0.094224 -1.468420 0.865975 0.029109 0.050080 0.997189 -0.047532\n4514 7.570288 -0.094276 -1.468347 0.865958 0.028436 0.050198 0.997204 -0.047499\n4515 7.579936 -0.094058 -1.469265 0.866059 0.029772 0.050169 0.997161 -0.047607\n4516 7.588272 -0.093982 -1.468632 0.866036 0.030897 0.048913 0.997194 -0.047505\n4517 7.596408 -0.094243 -1.468428 0.865979 0.028822 0.050116 0.997196 -0.047511\n4518 7.605386 -0.094039 -1.468429 0.866027 0.030591 0.049206 0.997186 -0.047563\n4519 7.613044 -0.094159 -1.469226 0.866023 0.029170 0.050118 0.997183 -0.047565\n4520 7.621279 -0.093930 -1.468333 0.866016 0.030774 0.048991 0.997199 -0.047394\n4521 7.628200 -0.093629 -1.468672 0.865912 0.032048 0.048829 0.997178 -0.047175\n4522 7.637252 -0.093955 -1.468413 0.865994 0.030540 0.049909 0.997148 -0.047674\n4523 7.644873 -0.094130 -1.469146 0.866017 0.029269 0.050198 0.997175 -0.047597\n4524 7.656318 -0.094008 -1.469309 0.866093 0.029890 0.050205 0.997156 -0.047598\n4525 7.662317 -0.094172 -1.468667 0.866031 0.029437 0.049695 0.997194 -0.047620\n4526 7.671217 -0.094007 -1.468195 0.865979 0.030242 0.049952 0.997147 -0.047837\n4527 7.678214 -0.094224 -1.468366 0.865978 0.029162 0.050082 0.997186 -0.047564\n4528 7.687594 -0.094244 -1.468418 0.865973 0.028907 0.050089 0.997196 -0.047504\n4529 7.697173 -0.093830 -1.468590 0.866000 0.031520 0.048507 0.997196 -0.047478\n4530 7.704848 -0.094073 -1.468653 0.866035 0.030256 0.049124 0.997205 -0.047469\n4531 7.713407 -0.094268 -1.468348 0.865953 0.028458 0.050226 0.997203 -0.047477\n4532 7.720946 -0.094261 -1.468359 0.865957 0.028551 0.050186 0.997202 -0.047476\n4533 7.728196 -0.094151 -1.469229 0.866024 0.029274 0.050164 0.997178 -0.047568\n4534 7.738274 -0.094134 -1.469132 0.866017 0.029300 0.050167 0.997178 -0.047552\n4535 7.746749 -0.093956 -1.468637 0.866036 0.031009 0.048862 0.997194 -0.047479\n4536 7.755040 -0.094159 -1.468271 0.865994 0.029627 0.049940 0.997173 -0.047688\n4537 7.761499 -0.094063 -1.468995 0.866017 0.031030 0.049099 0.997216 -0.046759\n4538 7.772031 -0.094118 -1.468349 0.866026 0.029912 0.049493 0.997192 -0.047588\n4539 7.779691 -0.094019 -1.468302 0.865991 0.030282 0.049920 0.997153 -0.047729\n4540 7.786932 -0.094096 -1.469246 0.866048 0.029518 0.050115 0.997174 -0.047557\n4541 7.795686 -0.093969 -1.468647 0.866036 0.030880 0.048914 0.997195 -0.047498\n4542 7.804429 -0.094166 -1.469157 0.866013 0.029177 0.050168 0.997181 -0.047562\n4543 7.811884 -0.094254 -1.468403 0.865968 0.028719 0.050137 0.997198 -0.047516\n4544 7.820949 -0.094212 -1.468332 0.865986 0.029230 0.050051 0.997182 -0.047626\n4545 7.830417 -0.094046 -1.468345 0.865992 0.030189 0.049950 0.997154 -0.047729\n4546 7.838614 -0.094221 -1.468462 0.865979 0.029264 0.050084 0.997184 -0.047540\n4547 7.845707 -0.094124 -1.468437 0.865989 0.029835 0.050056 0.997162 -0.047668\n4548 7.854454 -0.094186 -1.469174 0.866001 0.029082 0.050180 0.997182 -0.047580\n4549 7.862487 -0.094260 -1.468378 0.865965 0.028668 0.050147 0.997200 -0.047497\n4550 7.869950 -0.094283 -1.468401 0.865947 0.028431 0.050200 0.997208 -0.047420\n4551 7.879696 -0.093984 -1.469042 0.866048 0.030419 0.049386 0.997186 -0.047494\n4552 7.887544 -0.094089 -1.468625 0.866213 0.030771 0.048994 0.997238 -0.046581\n4553 7.894825 -0.094038 -1.468205 0.865973 0.030124 0.050005 0.997149 -0.047820\n4554 7.903412 -0.093867 -1.469099 0.865815 0.031644 0.048827 0.997206 -0.046847\n4555 7.913118 -0.093996 -1.468218 0.865975 0.030325 0.049926 0.997149 -0.047761\n4556 7.920660 -0.093923 -1.468458 0.865992 0.030600 0.049908 0.997146 -0.047676\n4557 7.929692 -0.093811 -1.468488 0.866022 0.030560 0.048968 0.997255 -0.046380\n4558 7.938190 -0.094061 -1.468393 0.866027 0.030331 0.049310 0.997188 -0.047593\n4559 7.944996 -0.093927 -1.468433 0.865993 0.030630 0.049909 0.997144 -0.047693\n4560 7.955354 -0.094118 -1.469216 0.866028 0.029342 0.050133 0.997178 -0.047559\n4561 7.962387 -0.094181 -1.468667 0.866022 0.029306 0.049718 0.997197 -0.047619\n4562 7.971115 -0.094126 -1.469217 0.866027 0.029394 0.050138 0.997176 -0.047555\n4563 7.979985 -0.093865 -1.468672 0.866016 0.031351 0.048668 0.997194 -0.047456\n4564 7.987871 -0.094160 -1.469203 0.866007 0.029132 0.050178 0.997181 -0.047574\n4565 7.996855 -0.093450 -1.468816 0.865680 0.031881 0.046883 0.997338 -0.045866\n4566 8.004200 -0.093990 -1.468978 0.865955 0.031190 0.049046 0.997217 -0.046697\n4567 8.013441 -0.094076 -1.468653 0.866028 0.030208 0.049192 0.997202 -0.047498\n4568 8.020825 -0.094225 -1.468347 0.865987 0.028966 0.049980 0.997196 -0.047582\n4569 8.028942 -0.094148 -1.469245 0.866020 0.029185 0.050162 0.997180 -0.047583\n4570 8.037905 -0.093838 -1.468632 0.865995 0.031557 0.048489 0.997194 -0.047501\n4571 8.045639 -0.094012 -1.468957 0.865993 0.031085 0.048997 0.997225 -0.046640\n4572 8.053201 -0.093842 -1.468516 0.866000 0.031458 0.048566 0.997195 -0.047477\n4573 8.062220 -0.094246 -1.468386 0.865971 0.028806 0.050098 0.997198 -0.047496\n4574 8.070464 -0.094234 -1.468442 0.865976 0.029089 0.050102 0.997189 -0.047511\n4575 8.078348 -0.093809 -1.468811 0.865979 0.031765 0.048508 0.997186 -0.047523\n4576 8.088026 -0.094111 -1.468041 0.865977 0.029758 0.049953 0.997162 -0.047819\n4577 8.097008 -0.094239 -1.468434 0.865980 0.029108 0.050081 0.997189 -0.047529\n4578 8.103804 -0.094105 -1.469076 0.866169 0.030283 0.049834 0.997180 -0.047243\n4579 8.113484 -0.094105 -1.469230 0.866041 0.029485 0.050134 0.997173 -0.047566\n4580 8.120435 -0.093836 -1.468897 0.866009 0.030998 0.048812 0.997209 -0.047240\n4581 8.128702 -0.094050 -1.468667 0.866029 0.030402 0.049137 0.997199 -0.047503\n4582 8.138020 -0.093791 -1.468507 0.866016 0.030594 0.048934 0.997258 -0.046321\n4583 8.147459 -0.093749 -1.468612 0.866008 0.030808 0.048651 0.997268 -0.046262\n4584 8.154616 -0.094186 -1.468653 0.866022 0.029240 0.049736 0.997199 -0.047597\n4585 8.161488 -0.094276 -1.468374 0.865942 0.028348 0.050214 0.997207 -0.047468\n4586 8.170427 -0.094202 -1.468367 0.865967 0.029338 0.050105 0.997177 -0.047622\n4587 8.178358 -0.094280 -1.468414 0.865942 0.028450 0.050201 0.997207 -0.047429\n4588 8.186945 -0.094240 -1.468385 0.865959 0.028888 0.050118 0.997195 -0.047504\n4589 8.196761 -0.093792 -1.468542 0.866017 0.030599 0.048940 0.997259 -0.046297\n4590 8.203382 -0.093876 -1.468806 0.866015 0.030971 0.048790 0.997209 -0.047275\n4591 8.213121 -0.094064 -1.469184 0.866037 0.029656 0.050159 0.997167 -0.047570\n4592 8.220643 -0.093987 -1.468587 0.866036 0.030677 0.049042 0.997196 -0.047473\n4593 8.228344 -0.094043 -1.469228 0.866056 0.029871 0.050185 0.997157 -0.047609\n4594 8.236665 -0.094079 -1.469201 0.866035 0.029611 0.050167 0.997167 -0.047577\n4595 8.247455 -0.094177 -1.469247 0.866003 0.029027 0.050200 0.997183 -0.047583\n4596 8.254396 -0.094011 -1.468650 0.866041 0.030705 0.048984 0.997196 -0.047512\n4597 8.263100 -0.093834 -1.468836 0.865801 0.031431 0.049040 0.997199 -0.046919\n4598 8.270525 -0.094264 -1.468381 0.865956 0.028661 0.050152 0.997200 -0.047483\n4599 8.278398 -0.094122 -1.469228 0.866028 0.029419 0.050148 0.997174 -0.047574\n4600 8.288554 -0.093748 -1.469166 0.865995 0.031236 0.048828 0.997215 -0.046928\n4601 8.295735 -0.094013 -1.468265 0.865978 0.030344 0.049794 0.997159 -0.047687\n4602 8.303245 -0.094217 -1.468243 0.865955 0.028940 0.050047 0.997195 -0.047535\n4603 8.311585 -0.094162 -1.469165 0.866006 0.029225 0.050150 0.997179 -0.047582\n4604 8.320909 -0.094233 -1.468417 0.865964 0.028925 0.050135 0.997193 -0.047504\n4605 8.328412 -0.093834 -1.469115 0.866031 0.031107 0.048965 0.997199 -0.047205\n4606 8.338410 -0.094163 -1.468377 0.866020 0.029563 0.049661 0.997193 -0.047614\n4607 8.345608 -0.093943 -1.469068 0.866045 0.030630 0.049344 0.997184 -0.047440\n4608 8.353591 -0.094078 -1.468678 0.866121 0.030638 0.049785 0.997181 -0.047039\n4609 8.361647 -0.094078 -1.468947 0.866068 0.031058 0.049054 0.997217 -0.046772\n4610 8.371432 -0.094232 -1.468405 0.865968 0.028954 0.050103 0.997193 -0.047503\n4611 8.380290 -0.093839 -1.468568 0.865999 0.031416 0.048567 0.997196 -0.047471\n4612 8.388808 -0.094205 -1.469232 0.865995 0.028943 0.050159 0.997188 -0.047574\n4613 8.395550 -0.094114 -1.468976 0.866157 0.030356 0.049785 0.997181 -0.047224\n4614 8.403394 -0.093919 -1.468320 0.865953 0.030843 0.049538 0.997161 -0.047579\n4615 8.414147 -0.094009 -1.468215 0.865965 0.030248 0.049989 0.997147 -0.047799\n4616 8.421220 -0.094210 -1.468728 0.865988 0.028899 0.049941 0.997197 -0.047636\n4617 8.429576 -0.094264 -1.468370 0.865943 0.028553 0.050209 0.997202 -0.047456\n4618 8.437829 -0.094126 -1.468668 0.866041 0.029965 0.049430 0.997194 -0.047568\n4619 8.444929 -0.093662 -1.468815 0.865866 0.031856 0.048802 0.997193 -0.047003\n4620 8.453223 -0.093889 -1.468268 0.865982 0.030864 0.048915 0.997203 -0.047338\n4621 8.464241 -0.094257 -1.468358 0.865945 0.028618 0.050182 0.997200 -0.047489\n4622 8.471105 -0.094154 -1.469247 0.866024 0.029326 0.050104 0.997180 -0.047556\n4623 8.479649 -0.094261 -1.468375 0.865958 0.028690 0.050124 0.997200 -0.047496\n4624 8.487332 -0.094089 -1.469359 0.866169 0.030106 0.049609 0.997252 -0.046062\n4625 8.494921 -0.094220 -1.468467 0.865974 0.029243 0.050064 0.997185 -0.047549\n4626 8.505390 -0.094280 -1.468375 0.865936 0.028316 0.050231 0.997208 -0.047448\n4627 8.512502 -0.094023 -1.468691 0.866024 0.030472 0.049077 0.997200 -0.047483\n4628 8.521226 -0.093904 -1.468828 0.866015 0.030824 0.048893 0.997205 -0.047353\n4629 8.528431 -0.093834 -1.468576 0.865987 0.031520 0.048528 0.997194 -0.047491\n4630 8.538057 -0.093797 -1.469114 0.865737 0.031782 0.048929 0.997194 -0.046897\n4631 8.545882 -0.094121 -1.468663 0.866040 0.029960 0.049379 0.997196 -0.047575\n4632 8.554098 -0.094212 -1.468733 0.865989 0.028887 0.049947 0.997197 -0.047637\n4633 8.563456 -0.094087 -1.468892 0.866038 0.030078 0.049468 0.997188 -0.047591\n4634 8.569923 -0.094059 -1.469223 0.866040 0.029702 0.050156 0.997165 -0.047578\n4635 8.579759 -0.094005 -1.468372 0.865984 0.030447 0.049836 0.997156 -0.047628\n4636 8.587632 -0.094154 -1.468538 0.866013 0.029646 0.049473 0.997208 -0.047434\n4637 8.596256 -0.094231 -1.468357 0.865971 0.029048 0.050074 0.997189 -0.047569\n4638 8.604417 -0.094276 -1.468316 0.865926 0.028251 0.050265 0.997205 -0.047516\n4639 8.611603 -0.094071 -1.468656 0.866041 0.030316 0.049233 0.997194 -0.047559\n4640 8.620172 -0.093833 -1.468591 0.865996 0.031465 0.048570 0.997195 -0.047463\n4641 8.629843 -0.093929 -1.468601 0.866017 0.031104 0.048804 0.997193 -0.047499\n4642 8.636807 -0.094252 -1.468420 0.865968 0.028867 0.050084 0.997196 -0.047517\n4643 8.645883 -0.094188 -1.468673 0.865999 0.029756 0.049313 0.997219 -0.047304\n4644 8.654608 -0.094052 -1.468935 0.866037 0.030259 0.049419 0.997186 -0.047569\n4645 8.661559 -0.094142 -1.468775 0.866027 0.029717 0.049519 0.997194 -0.047628\n4646 8.671161 -0.094265 -1.468383 0.865959 0.028657 0.050080 0.997203 -0.047508\n4647 8.679112 -0.093653 -1.469183 0.865928 0.031166 0.048148 0.997303 -0.045803\n4648 8.687857 -0.094202 -1.468727 0.866005 0.029167 0.049841 0.997194 -0.047638\n4649 8.694885 -0.094171 -1.468373 0.865965 0.029580 0.050038 0.997171 -0.047656\n4650 8.704699 -0.094267 -1.468372 0.865941 0.028580 0.050195 0.997202 -0.047461\n4651 8.712991 -0.094270 -1.468378 0.865942 0.028513 0.050194 0.997204 -0.047464\n4652 8.721006 -0.094009 -1.468650 0.866025 0.030689 0.049013 0.997195 -0.047519\n4653 8.728594 -0.094183 -1.468726 0.866018 0.029337 0.049777 0.997193 -0.047629\n4654 8.736734 -0.094092 -1.468669 0.865987 0.030493 0.049038 0.997206 -0.047386\n4655 8.744758 -0.094124 -1.468590 0.866005 0.030073 0.049272 0.997207 -0.047386\n4656 8.753182 -0.094272 -1.468349 0.865929 0.028221 0.050252 0.997208 -0.047488\n4657 8.763266 -0.093886 -1.468547 0.866087 0.031457 0.049111 0.997225 -0.046264\n4658 8.771076 -0.094228 -1.468274 0.865981 0.028937 0.050008 0.997194 -0.047610\n4659 8.779396 -0.094027 -1.468276 0.865999 0.030450 0.049304 0.997184 -0.047599\n4660 8.787904 -0.093621 -1.468668 0.865923 0.032154 0.048818 0.997173 -0.047207\n4661 8.794963 -0.093887 -1.468328 0.866042 0.030217 0.049069 0.997233 -0.046972\n4662 8.804587 -0.094241 -1.468389 0.865983 0.028839 0.049964 0.997201 -0.047555\n4663 8.812245 -0.094095 -1.468633 0.866209 0.030631 0.049029 0.997243 -0.046513\n4664 8.819921 -0.094125 -1.468642 0.866032 0.029993 0.049150 0.997213 -0.047439\n4665 8.828340 -0.094285 -1.468386 0.865956 0.028463 0.050123 0.997208 -0.047463\n4666 8.837691 -0.094138 -1.468213 0.866012 0.029447 0.049522 0.997206 -0.047549\n4667 8.844892 -0.093988 -1.468220 0.865975 0.030444 0.049560 0.997170 -0.047632\n4668 8.853586 -0.094296 -1.468379 0.865955 0.028395 0.050125 0.997210 -0.047470\n4669 8.863188 -0.094235 -1.468292 0.865973 0.029035 0.050007 0.997191 -0.047611\n4670 8.869884 -0.093990 -1.468636 0.866031 0.030815 0.048811 0.997202 -0.047502\n4671 8.878202 -0.094069 -1.468661 0.866049 0.030338 0.049055 0.997202 -0.047550\n4672 8.887472 -0.094097 -1.468153 0.865997 0.029937 0.049626 0.997180 -0.047672\n4673 8.894884 -0.094021 -1.468647 0.866038 0.030656 0.048922 0.997200 -0.047533\n4674 8.903259 -0.094228 -1.468650 0.866014 0.028944 0.049786 0.997203 -0.047650\n4675 8.915105 -0.094169 -1.469274 0.866024 0.029033 0.050077 0.997190 -0.047563\n4676 8.921098 -0.094081 -1.468658 0.866041 0.030265 0.049110 0.997202 -0.047550\n4677 8.929474 -0.093975 -1.468277 0.865987 0.030433 0.049754 0.997158 -0.047697\n4678 8.937285 -0.094189 -1.469280 0.866022 0.029018 0.050055 0.997192 -0.047554\n4679 8.944905 -0.094073 -1.469175 0.866055 0.029754 0.050041 0.997170 -0.047566\n4680 8.954582 -0.093845 -1.468825 0.865820 0.031350 0.048976 0.997201 -0.046992\n4681 8.962481 -0.094206 -1.468736 0.866024 0.029256 0.049675 0.997200 -0.047641\n4682 8.971073 -0.094151 -1.469174 0.866026 0.029239 0.050076 0.997184 -0.047550\n4683 8.979684 -0.094212 -1.468314 0.865980 0.029269 0.049972 0.997185 -0.047628\n4684 8.987882 -0.094172 -1.468951 0.866185 0.030232 0.049618 0.997202 -0.047031\n4685 8.996742 -0.094271 -1.468385 0.865968 0.028706 0.050102 0.997201 -0.047490\n4686 9.004417 -0.094032 -1.469295 0.866081 0.029831 0.050152 0.997161 -0.047595\n4687 9.014541 -0.094114 -1.469218 0.866037 0.029455 0.050122 0.997175 -0.047567\n4688 9.020428 -0.094204 -1.468358 0.865978 0.029342 0.050043 0.997179 -0.047631\n4689 9.028295 -0.094091 -1.469155 0.866043 0.029599 0.050091 0.997173 -0.047560\n4690 9.037031 -0.094177 -1.469204 0.866014 0.029321 0.050084 0.997178 -0.047623\n4691 9.048273 -0.094135 -1.468337 0.866012 0.030318 0.049560 0.997168 -0.047751\n4692 9.053937 -0.094177 -1.468397 0.865987 0.030015 0.049889 0.997169 -0.047589\n4693 9.061866 -0.094164 -1.468404 0.866011 0.030480 0.049666 0.997157 -0.047764\n4694 9.070764 -0.094066 -1.468674 0.866030 0.032094 0.048787 0.997145 -0.047874\n4695 9.078310 -0.094015 -1.468591 0.866061 0.031501 0.049474 0.997138 -0.047715\n4696 9.088218 -0.093966 -1.468601 0.866039 0.032223 0.049057 0.997126 -0.047897\n4697 9.095663 -0.094078 -1.468570 0.866068 0.031086 0.049923 0.997122 -0.047843\n4698 9.104502 -0.094141 -1.468647 0.865818 0.031849 0.047911 0.997207 -0.047634\n4699 9.112599 -0.094098 -1.468782 0.866190 0.032522 0.049275 0.997099 -0.048046\n4700 9.120753 -0.094133 -1.468968 0.866237 0.032554 0.049486 0.997101 -0.047757\n4701 9.129267 -0.094225 -1.468555 0.865984 0.026501 0.050622 0.997247 -0.047260\n4702 9.138004 -0.094631 -1.468880 0.866036 0.028431 0.049958 0.997189 -0.048056\n4703 9.146147 -0.094439 -1.468775 0.865995 0.027653 0.050511 0.997199 -0.047732\n4704 9.154649 -0.094660 -1.468942 0.865957 0.030144 0.049521 0.997153 -0.048211\n4705 9.162445 -0.094508 -1.468571 0.865978 0.027977 0.050940 0.997197 -0.047116\n4706 9.169964 -0.094202 -1.468510 0.865928 0.028270 0.051367 0.997170 -0.047061\n4707 9.179405 -0.094239 -1.468458 0.865894 0.027971 0.051913 0.997126 -0.047562\n4708 9.187513 -0.094090 -1.468629 0.865811 0.027916 0.051220 0.997177 -0.047277\n4709 9.196335 -0.094095 -1.468656 0.865826 0.028107 0.051262 0.997173 -0.047212\n4710 9.205496 -0.094149 -1.468601 0.865772 0.027363 0.051656 0.997162 -0.047443\n4711 9.212009 -0.094352 -1.468669 0.865923 0.029607 0.050198 0.997145 -0.048012\n4712 9.220073 -0.094362 -1.468673 0.865930 0.029668 0.050107 0.997144 -0.048086\n4713 9.231606 -0.094343 -1.468706 0.865945 0.030015 0.049872 0.997149 -0.048026\n4714 9.237449 -0.094611 -1.468978 0.865607 0.032169 0.047590 0.997124 -0.049440\n4715 9.246383 -0.094122 -1.468606 0.865780 0.027535 0.051692 0.997164 -0.047253\n4716 9.254878 -0.094119 -1.468637 0.865807 0.027782 0.051527 0.997170 -0.047175\n4717 9.261781 -0.094014 -1.468828 0.865912 0.029890 0.050345 0.997167 -0.047221\n4718 9.272584 -0.093671 -1.469024 0.865737 0.031154 0.050452 0.997090 -0.047921\n4719 9.279259 -0.094082 -1.468652 0.865838 0.028398 0.050834 0.997190 -0.047127\n4720 9.289174 -0.094330 -1.468645 0.865780 0.032513 0.048306 0.997095 -0.049103\n4721 9.296087 -0.094380 -1.468892 0.865913 0.031794 0.048182 0.997160 -0.048359\n4722 9.303851 -0.094025 -1.468768 0.865585 0.032139 0.048133 0.997159 -0.048220\n4723 9.312593 -0.093904 -1.468863 0.865829 0.032057 0.048392 0.997187 -0.047428\n4724 9.321664 -0.094174 -1.468717 0.865617 0.032047 0.048384 0.997165 -0.047890\n4725 9.329524 -0.094092 -1.468526 0.866344 0.026376 0.050784 0.997231 -0.047487\n4726 9.338846 -0.094050 -1.468779 0.866052 0.032816 0.049388 0.997099 -0.047720\n4727 9.346804 -0.094205 -1.468357 0.866051 0.031625 0.049020 0.997139 -0.048065\n4728 9.356456 -0.094285 -1.468774 0.866060 0.030619 0.048944 0.997182 -0.047902\n4729 9.362222 -0.094163 -1.468593 0.865925 0.030902 0.049191 0.997157 -0.047981\n4730 9.369887 -0.094306 -1.468733 0.865905 0.029798 0.049454 0.997177 -0.047999\n4731 9.378194 -0.093988 -1.468480 0.865878 0.030706 0.048861 0.997190 -0.047780\n4732 9.387757 -0.093762 -1.468577 0.865819 0.031439 0.048209 0.997258 -0.046527\n4733 9.396306 -0.094347 -1.468683 0.865910 0.029531 0.049501 0.997178 -0.048108\n4734 9.405920 -0.093816 -1.468525 0.865843 0.031160 0.048500 0.997219 -0.047228\n4735 9.412153 -0.093759 -1.468567 0.865841 0.032320 0.048246 0.997152 -0.048125\n4736 9.420113 -0.093937 -1.468553 0.865883 0.032279 0.049473 0.997172 -0.046462\n4737 9.429189 -0.093965 -1.468467 0.865718 0.031744 0.048893 0.997217 -0.046487\n4738 9.438069 -0.093851 -1.468401 0.865977 0.028502 0.052880 0.997075 -0.047248\n4739 9.444715 -0.093971 -1.468372 0.865739 0.027376 0.054033 0.997053 -0.047074\n4740 9.453194 -0.094065 -1.468655 0.866024 0.029269 0.051874 0.997075 -0.047887\n4741 9.463548 -0.093946 -1.468376 0.865844 0.027864 0.052846 0.997086 -0.047443\n4742 9.470385 -0.094444 -1.468495 0.865898 0.028265 0.052294 0.997064 -0.048267\n4743 9.479281 -0.093968 -1.468403 0.865814 0.027745 0.052447 0.997116 -0.047320\n4744 9.488830 -0.094347 -1.468638 0.866019 0.029757 0.050599 0.997123 -0.047951\n4745 9.494992 -0.094983 -1.468898 0.865978 0.029309 0.050802 0.997083 -0.048846\n4746 9.504722 -0.093820 -1.468523 0.865898 0.031283 0.050001 0.997083 -0.048454\n4747 9.512302 -0.094179 -1.468283 0.865867 0.028367 0.051492 0.997136 -0.047582\n4748 9.521326 -0.094164 -1.468574 0.866006 0.030111 0.050037 0.997141 -0.047946\n4749 9.528004 -0.093880 -1.468493 0.865984 0.029339 0.050756 0.997146 -0.047578\n4750 9.538873 -0.094078 -1.468388 0.865853 0.028015 0.051535 0.997155 -0.047345\n4751 9.546361 -0.094158 -1.468439 0.865981 0.030564 0.049851 0.997128 -0.048132\n4752 9.554607 -0.093999 -1.468626 0.865933 0.030887 0.049366 0.997159 -0.047776\n4753 9.562251 -0.094100 -1.468406 0.865783 0.030548 0.049875 0.997073 -0.049237\n4754 9.569993 -0.093801 -1.468170 0.865659 0.032057 0.049311 0.997060 -0.049111\n4755 9.579567 -0.093719 -1.468441 0.865385 0.032334 0.048690 0.997142 -0.047871\n4756 9.588113 -0.093962 -1.468659 0.865641 0.030741 0.049145 0.997179 -0.047679\n4757 9.595993 -0.093680 -1.468604 0.865479 0.031750 0.048389 0.997187 -0.047617\n4758 9.604705 -0.093619 -1.468362 0.865427 0.031630 0.048534 0.997193 -0.047431\n4759 9.611574 -0.093470 -1.468269 0.864992 0.032668 0.048419 0.997111 -0.048558\n4760 9.621449 -0.093944 -1.468911 0.865287 0.031303 0.049482 0.997131 -0.047975\n4761 9.629197 -0.093993 -1.468336 0.865206 0.030992 0.049635 0.997116 -0.048335\n4762 9.637933 -0.093969 -1.468807 0.865240 0.030748 0.049546 0.997152 -0.047833\n4763 9.647884 -0.093457 -1.468669 0.865176 0.032424 0.049687 0.997063 -0.048435\n4764 9.655653 -0.094165 -1.468922 0.865271 0.030365 0.050323 0.997097 -0.048401\n4765 9.663235 -0.093138 -1.468266 0.865025 0.033531 0.048201 0.997080 -0.048828\n4766 9.670816 -0.094632 -1.469027 0.865433 0.029587 0.050689 0.997093 -0.048597\n4767 9.679375 -0.094582 -1.468773 0.865540 0.029603 0.050810 0.997089 -0.048530\n4768 9.687824 -0.094083 -1.468743 0.865678 0.030828 0.049690 0.997143 -0.047814\n4769 9.695190 -0.094129 -1.468677 0.865814 0.030547 0.049642 0.997160 -0.047686\n4770 9.704304 -0.094154 -1.468598 0.865879 0.030164 0.049577 0.997170 -0.047801\n4771 9.712762 -0.094032 -1.468584 0.865895 0.030430 0.049403 0.997161 -0.047993\n4772 9.719995 -0.093958 -1.468522 0.865890 0.030595 0.050133 0.997095 -0.048504\n4773 9.732188 -0.094620 -1.468539 0.865936 0.029191 0.050667 0.997075 -0.049220\n4774 9.737459 -0.094306 -1.468547 0.866055 0.029593 0.050409 0.997126 -0.048207\n4775 9.746324 -0.093237 -1.468572 0.865918 0.034764 0.049646 0.996986 -0.048431\n4776 9.754742 -0.093642 -1.468165 0.865929 0.030320 0.050898 0.997113 -0.047496\n4777 9.761663 -0.093421 -1.468514 0.865831 0.033618 0.049908 0.997008 -0.048515\n4778 9.771822 -0.093951 -1.467962 0.865892 0.031778 0.050021 0.997069 -0.048386\n4779 9.779189 -0.093630 -1.468514 0.865787 0.033024 0.050038 0.997008 -0.048799\n4780 9.788604 -0.093984 -1.468567 0.865848 0.030669 0.050469 0.997112 -0.047760\n4781 9.796521 -0.093410 -1.468625 0.865650 0.034505 0.050022 0.996986 -0.048230\n4782 9.804149 -0.093638 -1.468586 0.865605 0.033199 0.050411 0.996968 -0.049109\n4783 9.812945 -0.094001 -1.468585 0.865716 0.030274 0.049213 0.997192 -0.047652\n4784 9.820594 -0.094124 -1.468606 0.865684 0.029579 0.049490 0.997195 -0.047720\n4785 9.828099 -0.093989 -1.468582 0.865564 0.030013 0.049176 0.997198 -0.047724\n4786 9.837692 -0.094685 -1.468685 0.865480 0.028705 0.050597 0.997123 -0.048594\n4787 9.846225 -0.093927 -1.468688 0.865408 0.030478 0.049345 0.997177 -0.047694\n4788 9.855283 -0.093927 -1.468492 0.865162 0.028089 0.051335 0.997168 -0.047242\n4789 9.862127 -0.093758 -1.468595 0.864830 0.032420 0.048776 0.997103 -0.048539\n4790 9.870270 -0.093913 -1.468595 0.864915 0.028516 0.051812 0.997120 -0.047485\n4791 9.879184 -0.094301 -1.468881 0.865038 0.030511 0.050160 0.997125 -0.047910\n4792 9.887676 -0.094080 -1.468576 0.864960 0.030413 0.049798 0.997133 -0.048186\n4793 9.894799 -0.094387 -1.468374 0.864939 0.029975 0.049376 0.997128 -0.048994\n4794 9.904561 -0.095141 -1.469228 0.864917 0.026944 0.050748 0.997157 -0.048746\n4795 9.912921 -0.095252 -1.469271 0.864938 0.026818 0.050505 0.997162 -0.048981\n4796 9.921403 -0.094575 -1.468814 0.865017 0.028011 0.049438 0.997203 -0.048561\n4797 9.929442 -0.094294 -1.468518 0.864921 0.029461 0.048214 0.997203 -0.048927\n4798 9.937721 -0.094687 -1.468768 0.864696 0.028867 0.047729 0.997206 -0.049692\n4799 9.944965 -0.094578 -1.468858 0.864882 0.028740 0.047930 0.997194 -0.049815\n4800 9.954657 -0.094574 -1.468981 0.864751 0.029401 0.047362 0.997175 -0.050339\n4801 9.962301 -0.094293 -1.469008 0.864550 0.030823 0.046176 0.997174 -0.050610\n4802 9.970088 -0.094232 -1.468886 0.864310 0.026912 0.049177 0.997147 -0.050558\n4803 9.978308 -0.093729 -1.468730 0.864264 0.028285 0.047956 0.997189 -0.050151\n4804 9.987982 -0.094126 -1.468978 0.864168 0.027620 0.048800 0.997141 -0.050660\n4805 9.995406 -0.094139 -1.468908 0.863938 0.027332 0.049563 0.997168 -0.049522\n4806 10.004857 -0.094256 -1.468891 0.863992 0.028095 0.049132 0.997143 -0.050019\n4807 10.012952 -0.094371 -1.468485 0.863743 0.031320 0.045515 0.997221 -0.049971\n4808 10.020012 -0.094219 -1.469020 0.864129 0.031612 0.045997 0.997131 -0.051128\n4809 10.029636 -0.094617 -1.469174 0.863968 0.031528 0.045045 0.997211 -0.050469\n4810 10.037438 -0.094488 -1.468780 0.864242 0.028341 0.048480 0.997140 -0.050586\n4811 10.046423 -0.094345 -1.468952 0.864294 0.028209 0.048463 0.997163 -0.050209\n4812 10.054784 -0.094205 -1.468852 0.864192 0.027231 0.049562 0.997135 -0.050236\n4813 10.061808 -0.094173 -1.468807 0.864170 0.027423 0.049722 0.997160 -0.049473\n4814 10.071705 -0.094567 -1.469020 0.864366 0.029945 0.047465 0.997145 -0.050525\n4815 10.079208 -0.094401 -1.468872 0.863923 0.027654 0.050102 0.997131 -0.049539\n4816 10.088525 -0.094864 -1.468430 0.863733 0.030208 0.046152 0.997260 -0.049294\n4817 10.096206 -0.094530 -1.468460 0.863611 0.029745 0.046646 0.997268 -0.048940\n4818 10.104454 -0.095397 -1.469350 0.863033 0.030999 0.042772 0.997395 -0.049125\n4819 10.112703 -0.094669 -1.469349 0.862658 0.027952 0.048298 0.997214 -0.049507\n4820 10.121056 -0.095126 -1.469529 0.862374 0.028868 0.046888 0.997216 -0.050287\n4821 10.128244 -0.094285 -1.469437 0.862067 0.029868 0.044985 0.997415 -0.047403\n4822 10.137469 -0.094670 -1.469159 0.861810 0.030416 0.044003 0.997356 -0.049182\n4823 10.146458 -0.094995 -1.470232 0.861600 0.033439 0.040883 0.997396 -0.049100\n4824 10.153310 -0.094725 -1.469740 0.861534 0.031058 0.042370 0.997432 -0.048671\n4825 10.162991 -0.094837 -1.470331 0.861533 0.031169 0.041422 0.997440 -0.049250\n4826 10.171073 -0.094748 -1.470167 0.861454 0.029231 0.041640 0.997569 -0.047613\n4827 10.178303 -0.095219 -1.470034 0.861614 0.030668 0.038819 0.997537 -0.049732\n4828 10.186795 -0.094936 -1.470312 0.861877 0.032152 0.037524 0.997573 -0.049052\n4829 10.196059 -0.095363 -1.470353 0.862098 0.029145 0.038785 0.997621 -0.048975\n4830 10.204446 -0.095612 -1.470423 0.862279 0.030497 0.036735 0.997662 -0.048902\n4831 10.213458 -0.096098 -1.470407 0.862848 0.027673 0.040010 0.997625 -0.048768\n4832 10.220529 -0.095853 -1.470000 0.863249 0.028807 0.040254 0.997647 -0.047428\n4833 10.228333 -0.095792 -1.469890 0.863430 0.026435 0.043942 0.997643 -0.045591\n4834 10.236634 -0.095676 -1.469794 0.863903 0.025940 0.044955 0.997698 -0.043644\n4835 10.246648 -0.096001 -1.469776 0.864467 0.027455 0.043269 0.997761 -0.042966\n4836 10.254135 -0.096079 -1.469599 0.865059 0.027408 0.043746 0.997784 -0.041978\n4837 10.262883 -0.095848 -1.469271 0.865572 0.027838 0.046905 0.997699 -0.040280\n4838 10.271509 -0.095396 -1.469108 0.865838 0.024918 0.049601 0.997677 -0.039482\n4839 10.278554 -0.095446 -1.469154 0.866348 0.025367 0.048199 0.997745 -0.039213\n4840 10.287935 -0.095086 -1.468873 0.866672 0.024269 0.050630 0.997637 -0.039588\n4841 10.295405 -0.095692 -1.469003 0.867483 0.024515 0.052193 0.997551 -0.039575\n4842 10.303077 -0.095642 -1.468773 0.868049 0.023139 0.053704 0.997467 -0.040500\n4843 10.311968 -0.095696 -1.468382 0.868695 0.020430 0.057934 0.997207 -0.042493\n4844 10.321447 -0.095546 -1.468139 0.869585 0.020854 0.057372 0.997295 -0.040946\n4845 10.329905 -0.095376 -1.467473 0.870336 0.020062 0.058496 0.997270 -0.040356\n4846 10.338150 -0.095944 -1.467496 0.871256 0.019395 0.059661 0.997183 -0.041105\n4847 10.346616 -0.095703 -1.466996 0.872093 0.019769 0.059756 0.997206 -0.040240\n4848 10.355370 -0.095816 -1.466686 0.872979 0.018623 0.060748 0.997189 -0.039700\n4849 10.362431 -0.095969 -1.466391 0.874048 0.019027 0.060490 0.997217 -0.039201\n4850 10.371959 -0.096110 -1.465997 0.875082 0.018290 0.061199 0.997220 -0.038388\n4851 10.379373 -0.096520 -1.465854 0.876318 0.020846 0.058815 0.997353 -0.037319\n4852 10.386706 -0.096623 -1.465212 0.877564 0.020056 0.060864 0.997282 -0.036362\n4853 10.396151 -0.096704 -1.464484 0.878951 0.018674 0.063251 0.997182 -0.035750\n4854 10.404234 -0.096774 -1.463934 0.880343 0.017540 0.066247 0.997073 -0.033896\n4855 10.411405 -0.097125 -1.463166 0.881747 0.019210 0.065463 0.997094 -0.033892\n4856 10.420760 -0.096703 -1.462521 0.883314 0.017938 0.068924 0.996940 -0.032219\n4857 10.429837 -0.097005 -1.461928 0.884911 0.019005 0.068899 0.996929 -0.031997\n4858 10.436674 -0.097518 -1.461430 0.886389 0.008799 0.073068 0.996846 -0.029693\n4859 10.444935 -0.097403 -1.460837 0.888091 0.008819 0.074280 0.996786 -0.028663\n4860 10.454573 -0.097867 -1.459867 0.889761 0.016183 0.073095 0.996770 -0.029080\n4861 10.461629 -0.097452 -1.458670 0.891547 0.016951 0.073891 0.996720 -0.028309\n4862 10.471777 -0.097674 -1.457620 0.894116 0.014867 0.076172 0.996615 -0.027116\n4863 10.479366 -0.097985 -1.457435 0.895528 0.017254 0.075623 0.996581 -0.028460\n4864 10.487709 -0.097692 -1.456822 0.897706 0.013744 0.076342 0.996602 -0.027711\n4865 10.496196 -0.096997 -1.455941 0.899734 0.018458 0.075306 0.996596 -0.028011\n4866 10.504283 -0.097613 -1.455291 0.901729 0.014629 0.075766 0.996599 -0.028924\n4867 10.512762 -0.098269 -1.454599 0.903628 0.012191 0.076226 0.996577 -0.029577\n4868 10.520979 -0.097315 -1.453933 0.905674 0.011294 0.076586 0.996532 -0.030509\n4869 10.528137 -0.097492 -1.452389 0.907813 0.016227 0.073640 0.996582 -0.033736\n4870 10.537015 -0.097810 -1.452338 0.910057 0.010746 0.074889 0.996632 -0.031628\n4871 10.546319 -0.097544 -1.450841 0.912391 0.012618 0.073555 0.996700 -0.031933\n4872 10.553192 -0.097573 -1.450198 0.914391 0.019339 0.069139 0.996863 -0.033307\n4873 10.561522 -0.097585 -1.448874 0.916832 0.019268 0.069444 0.996822 -0.033934\n4874 10.571216 -0.097487 -1.447731 0.919306 0.016618 0.071705 0.996684 -0.034687\n4875 10.578108 -0.097977 -1.446153 0.921372 0.008590 0.072594 0.996712 -0.034943\n4876 10.586651 -0.097240 -1.444855 0.924217 0.017309 0.071053 0.996699 -0.035259\n4877 10.596078 -0.097546 -1.443829 0.926613 0.010291 0.071209 0.996760 -0.035961\n4878 10.604107 -0.097348 -1.442204 0.929400 0.020187 0.066932 0.996900 -0.036098\n4879 10.612815 -0.097072 -1.440591 0.932238 0.018041 0.068930 0.996802 -0.036192\n4880 10.620162 -0.097143 -1.439436 0.934967 0.020914 0.066422 0.996898 -0.036665\n4881 10.628532 -0.097078 -1.437662 0.937811 0.022179 0.066893 0.996820 -0.037202\n4882 10.639695 -0.096925 -1.435975 0.940820 0.023539 0.067417 0.996727 -0.037909\n4883 10.645977 -0.096720 -1.433904 0.943903 0.023030 0.070802 0.996500 -0.037997\n4884 10.655342 -0.096876 -1.432274 0.946883 0.027426 0.068065 0.996527 -0.039355\n4885 10.661972 -0.096628 -1.430314 0.949952 0.026621 0.072212 0.996269 -0.039044\n4886 10.669913 -0.097011 -1.428439 0.953095 0.030773 0.069705 0.996314 -0.039399\n4887 10.678938 -0.096153 -1.426433 0.956157 0.031029 0.071858 0.996156 -0.039330\n4888 10.688204 -0.096106 -1.424342 0.959102 0.032123 0.071909 0.996115 -0.039396\n4889 10.695043 -0.096220 -1.422257 0.962368 0.034374 0.070072 0.996155 -0.039796\n4890 10.705264 -0.095908 -1.420275 0.965525 0.034698 0.069173 0.996244 -0.038844\n4891 10.712633 -0.095829 -1.418083 0.968655 0.036126 0.068369 0.996232 -0.039284\n4892 10.719809 -0.096027 -1.416309 0.972017 0.037710 0.065903 0.996309 -0.040041\n4893 10.730221 -0.095668 -1.414299 0.975183 0.043411 0.059371 0.996500 -0.039720\n4894 10.737010 -0.095543 -1.412037 0.978261 0.044054 0.058618 0.996515 -0.039756\n4895 10.746118 -0.095705 -1.409688 0.981232 0.042686 0.059113 0.996531 -0.040113\n4896 10.753854 -0.094842 -1.407858 0.984185 0.049076 0.056022 0.996420 -0.040016\n4897 10.762305 -0.095197 -1.405181 0.987352 0.047617 0.056872 0.996421 -0.040551\n4898 10.771857 -0.095109 -1.402705 0.990402 0.047651 0.056881 0.996408 -0.040808\n4899 10.779304 -0.094877 -1.400225 0.993400 0.049112 0.055997 0.996387 -0.040810\n4900 10.787036 -0.095282 -1.397821 0.996351 0.047781 0.056666 0.996391 -0.041358\n4901 10.794927 -0.094974 -1.395182 0.999196 0.048850 0.056497 0.996358 -0.041146\n4902 10.804608 -0.094672 -1.392587 1.001967 0.050542 0.056488 0.996291 -0.040729\n4903 10.811842 -0.094791 -1.390083 1.004831 0.050718 0.057882 0.996202 -0.040723\n4904 10.821008 -0.094678 -1.387460 1.007666 0.050698 0.059578 0.996122 -0.040263\n4905 10.828179 -0.094727 -1.384890 1.010500 0.050372 0.061305 0.996056 -0.039712\n4906 10.838234 -0.094092 -1.382459 1.013204 0.054014 0.062031 0.995897 -0.037723\n4907 10.844969 -0.093879 -1.379672 1.015908 0.055410 0.063901 0.995719 -0.037279\n4908 10.854971 -0.093755 -1.376944 1.018583 0.056177 0.065825 0.995577 -0.036580\n4909 10.863003 -0.093023 -1.374387 1.021426 0.059291 0.065735 0.995449 -0.035292\n4910 10.869981 -0.092663 -1.371867 1.024127 0.060500 0.066785 0.995354 -0.033898\n4911 10.879958 -0.091779 -1.369367 1.026804 0.061276 0.067839 0.995291 -0.032230\n4912 10.887281 -0.091334 -1.366866 1.029276 0.062665 0.068488 0.995177 -0.031716\n4913 10.897003 -0.090898 -1.364369 1.032054 0.060052 0.070773 0.995242 -0.029638\n4914 10.903363 -0.090178 -1.361996 1.034309 0.061330 0.070589 0.995202 -0.028789\n4915 10.911541 -0.089374 -1.359668 1.036676 0.059433 0.071906 0.995299 -0.026043\n4916 10.920761 -0.088584 -1.357650 1.038875 0.059322 0.070582 0.995399 -0.026065\n4917 10.928875 -0.087283 -1.354736 1.041043 0.058805 0.069337 0.995576 -0.023742\n4918 10.937688 -0.086877 -1.353671 1.043679 0.052924 0.067889 0.996123 -0.018166\n4919 10.945539 -0.085821 -1.350509 1.045483 0.051931 0.065070 0.996409 -0.015447\n4920 10.953096 -0.084948 -1.348554 1.047331 0.051301 0.060653 0.996768 -0.011991\n4921 10.961525 -0.084191 -1.346458 1.049807 0.045332 0.057450 0.997289 -0.007752\n4922 10.971367 -0.082954 -1.344212 1.051508 0.046295 0.052880 0.997518 -0.004251\n4923 10.978642 -0.082088 -1.341977 1.053430 0.045183 0.048593 0.997795 -0.001740\n4924 10.987135 -0.081075 -1.339613 1.055280 0.043663 0.044827 0.998040 0.000758\n4925 10.995397 -0.080273 -1.336891 1.057495 0.042218 0.041388 0.998250 0.001475\n4926 11.003165 -0.079333 -1.334728 1.059762 0.038908 0.038072 0.998515 0.002301\n4927 11.013277 -0.078425 -1.332151 1.061714 0.039366 0.034981 0.998611 0.001711\n4928 11.020567 -0.076418 -1.329283 1.063445 0.042400 0.030678 0.998628 0.001580\n4929 11.029659 -0.075688 -1.326784 1.065339 0.043458 0.029008 0.998634 0.000582\n4930 11.037171 -0.074365 -1.323870 1.066939 0.042205 0.026377 0.998761 -0.000225\n4931 11.046677 -0.073592 -1.321525 1.068530 0.041891 0.024402 0.998823 -0.001689\n4932 11.053435 -0.072885 -1.318480 1.070360 0.037379 0.024235 0.999005 -0.002043\n4933 11.063039 -0.071250 -1.315452 1.071911 0.037737 0.022801 0.999026 -0.001846\n4934 11.071019 -0.070290 -1.312463 1.073497 0.032544 0.023817 0.999185 -0.001923\n4935 11.079444 -0.068878 -1.309030 1.075051 0.031574 0.022803 0.999240 -0.001331\n4936 11.088261 -0.067568 -1.305898 1.076837 0.026110 0.025319 0.999338 -0.000417\n4937 11.095273 -0.066669 -1.302146 1.078391 0.018943 0.027726 0.999436 0.000497\n4938 11.104345 -0.065432 -1.298403 1.079915 0.014227 0.030157 0.999443 0.001379\n4939 11.111901 -0.064260 -1.295111 1.081247 0.008244 0.033543 0.999400 0.002523\n4940 11.119780 -0.062629 -1.290948 1.082658 0.006364 0.035739 0.999332 0.004127\n4941 11.128166 -0.061446 -1.288140 1.083785 0.004412 0.039488 0.999198 0.004923\n4942 11.137715 -0.060053 -1.284259 1.085286 -0.000453 0.042995 0.999055 0.006306\n4943 11.144708 -0.058804 -1.280888 1.086650 -0.004727 0.046080 0.998905 0.006580\n4944 11.153728 -0.057232 -1.278357 1.088097 -0.006648 0.049215 0.998744 0.006681\n4945 11.162800 -0.055728 -1.273948 1.089428 -0.007620 0.052126 0.998595 0.005790\n4946 11.169946 -0.053973 -1.270450 1.090823 -0.006755 0.054019 0.998508 0.004333\n4947 11.178027 -0.052522 -1.267867 1.092246 -0.007503 0.056259 0.998385 0.002472\n4948 11.186450 -0.050905 -1.265101 1.093827 -0.006143 0.056740 0.998370 0.000450\n4949 11.196221 -0.049267 -1.261209 1.095235 -0.005917 0.058640 0.998258 -0.002576\n4950 11.204118 -0.047411 -1.257595 1.096691 -0.003151 0.059302 0.998223 -0.005023\n4951 11.212866 -0.045190 -1.254816 1.098137 0.001370 0.060011 0.998168 -0.007601\n4952 11.220798 -0.043521 -1.251657 1.099417 0.003633 0.062285 0.998000 -0.010185\n4953 11.229475 -0.041657 -1.248914 1.100982 0.008341 0.064026 0.997841 -0.012006\n4954 11.237893 -0.039897 -1.245495 1.102467 0.012102 0.066669 0.997602 -0.014137\n4955 11.245205 -0.037784 -1.243039 1.103829 0.018561 0.068078 0.997386 -0.015558\n4956 11.254244 -0.036946 -1.239815 1.105568 0.017705 0.072108 0.997079 -0.017913\n4957 11.262419 -0.035418 -1.236610 1.107438 0.022071 0.073516 0.996863 -0.019313\n4958 11.271538 -0.033915 -1.234202 1.109063 0.025507 0.073931 0.996720 -0.020794\n4959 11.279159 -0.033103 -1.231407 1.110865 0.021788 0.075146 0.996691 -0.022051\n4960 11.287643 -0.031615 -1.228576 1.112639 0.024806 0.075816 0.996570 -0.022045\n4961 11.296105 -0.030349 -1.225777 1.114425 0.024454 0.076140 0.996559 -0.021789\n4962 11.304978 -0.028690 -1.223672 1.116446 0.024942 0.074290 0.996739 -0.019263\n4963 11.312429 -0.027967 -1.220320 1.118330 0.023117 0.073750 0.996825 -0.019151\n4964 11.321600 -0.027414 -1.217666 1.120396 0.020835 0.073309 0.996933 -0.017789\n4965 11.329374 -0.026544 -1.215003 1.122372 0.020099 0.072498 0.997044 -0.015586\n4966 11.336451 -0.025955 -1.212238 1.124269 0.019662 0.071519 0.997150 -0.013788\n4967 11.346064 -0.025661 -1.209673 1.126254 0.019144 0.071752 0.997170 -0.011723\n4968 11.353963 -0.025051 -1.207583 1.128245 0.018040 0.070408 0.997312 -0.009270\n4969 11.361963 -0.024828 -1.205091 1.130292 0.017360 0.070625 0.997330 -0.006619\n4970 11.372392 -0.024999 -1.202613 1.132395 0.015190 0.072169 0.997268 -0.004293\n4971 11.378907 -0.024661 -1.200269 1.134482 0.017511 0.072423 0.997220 -0.001175\n4972 11.386641 -0.024532 -1.198319 1.136607 0.016711 0.074186 0.997103 0.001855\n4973 11.394663 -0.024468 -1.196080 1.138611 0.016230 0.075885 0.996973 0.004782\n4974 11.403250 -0.024274 -1.194277 1.140560 0.016174 0.077813 0.996800 0.008552\n4975 11.412912 -0.024512 -1.192065 1.142689 0.014140 0.079446 0.996680 0.010852\n4976 11.421506 -0.024751 -1.190253 1.144722 0.014017 0.080621 0.996553 0.013622\n4977 11.431539 -0.024897 -1.188532 1.146733 0.017054 0.080653 0.996464 0.016258\n4978 11.436803 -0.025138 -1.186566 1.148687 0.017930 0.081283 0.996345 0.019173\n4979 11.444676 -0.025593 -1.185435 1.150682 0.018733 0.082041 0.996191 0.022835\n4980 11.453855 -0.026209 -1.184303 1.152738 0.018167 0.083080 0.996048 0.025604\n4981 11.462987 -0.026765 -1.182424 1.154582 0.016939 0.084685 0.995854 0.028575\n4982 11.471143 -0.026708 -1.181519 1.156649 0.017336 0.084637 0.995698 0.033502\n4983 11.478975 -0.028074 -1.179733 1.158152 0.013198 0.087639 0.995470 0.034408\n4984 11.486545 -0.028098 -1.178734 1.159934 0.017299 0.087264 0.995342 0.037152\n4985 11.495030 -0.028453 -1.177497 1.161323 0.018218 0.088388 0.995148 0.039200\n4986 11.504659 -0.028974 -1.176545 1.163023 0.014622 0.089399 0.995007 0.041904\n4987 11.511821 -0.029482 -1.175754 1.164416 0.015942 0.090225 0.994846 0.043433\n4988 11.521131 -0.030111 -1.174780 1.165826 0.012554 0.091479 0.994714 0.044929\n4989 11.529630 -0.030466 -1.174077 1.167131 0.015498 0.091211 0.994668 0.045572\n4990 11.536700 -0.030594 -1.173136 1.168527 0.014716 0.090764 0.994641 0.047264\n4991 11.544887 -0.031747 -1.173492 1.169600 0.013183 0.091518 0.994604 0.047055\n4992 11.553935 -0.032311 -1.172464 1.170512 0.012702 0.092011 0.994589 0.046533\n4993 11.562124 -0.032540 -1.172193 1.171475 0.013765 0.091600 0.994598 0.046840\n4994 11.569992 -0.032971 -1.172196 1.172312 0.013970 0.092220 0.994556 0.046468\n4995 11.580438 -0.032753 -1.172745 1.173204 0.016614 0.091329 0.994556 0.047349\n4996 11.587518 -0.033488 -1.172350 1.173617 0.018875 0.093677 0.994374 0.045693\n4997 11.596190 -0.034163 -1.171997 1.174559 0.016520 0.093499 0.994436 0.045625\n4998 11.603863 -0.034589 -1.171917 1.175226 0.017778 0.094141 0.994376 0.045147\n4999 11.612697 -0.035274 -1.171666 1.175689 0.017105 0.095809 0.994238 0.044935\n5000 11.621796 -0.035413 -1.171970 1.176365 0.020642 0.095447 0.994214 0.044741\n5001 11.628344 -0.036045 -1.171625 1.176775 0.017127 0.097471 0.994079 0.044859\n5002 11.637736 -0.036061 -1.171813 1.177159 0.020676 0.097358 0.993993 0.045526\n5003 11.645428 -0.036712 -1.171763 1.177485 0.016000 0.099281 0.993834 0.046695\n5004 11.653043 -0.036797 -1.171988 1.177858 0.017798 0.098920 0.993753 0.048501\n5005 11.661654 -0.036902 -1.172180 1.178113 0.018823 0.098726 0.993694 0.049718\n5006 11.671664 -0.037146 -1.172382 1.178234 0.018944 0.099338 0.993541 0.051478\n5007 11.678732 -0.037245 -1.173105 1.178447 0.017586 0.098988 0.993474 0.053858\n5008 11.686529 -0.037296 -1.173192 1.178404 0.019226 0.098609 0.993396 0.055419\n5009 11.696273 -0.037395 -1.173432 1.178522 0.017665 0.097810 0.993379 0.057615\n5010 11.704095 -0.037626 -1.173362 1.178389 0.017932 0.097758 0.993320 0.058631\n5011 11.712935 -0.037506 -1.173593 1.178313 0.017281 0.097277 0.993311 0.059772\n5012 11.720616 -0.037119 -1.173929 1.178345 0.019021 0.096443 0.993308 0.060636\n5013 11.729119 -0.036686 -1.174029 1.178341 0.020930 0.096122 0.993300 0.060644\n5014 11.736475 -0.036058 -1.174333 1.178316 0.024008 0.095724 0.993279 0.060483\n5015 11.746623 -0.035495 -1.174369 1.178119 0.027150 0.095867 0.993227 0.059769\n5016 11.754097 -0.034982 -1.174361 1.178271 0.028996 0.096278 0.993183 0.058971\n5017 11.762793 -0.034860 -1.174445 1.178188 0.027016 0.097347 0.993160 0.058536\n5018 11.771041 -0.034285 -1.174554 1.178169 0.030688 0.097420 0.993074 0.058064\n5019 11.779096 -0.033659 -1.174264 1.178021 0.035447 0.096909 0.992972 0.057949\n5020 11.786581 -0.033156 -1.174715 1.177857 0.036903 0.097508 0.992874 0.057717\n5021 11.794942 -0.032521 -1.174738 1.177675 0.040028 0.097351 0.992756 0.057934\n5022 11.804589 -0.032084 -1.174731 1.177486 0.041975 0.097894 0.992626 0.057871\n5023 11.812493 -0.031654 -1.174632 1.177278 0.043423 0.098649 0.992496 0.057736\n5024 11.820858 -0.031298 -1.174557 1.176965 0.046086 0.099378 0.992347 0.056993\n5025 11.829361 -0.030922 -1.174315 1.176833 0.045025 0.100331 0.992288 0.057195\n5026 11.836548 -0.030560 -1.173992 1.176605 0.043614 0.102412 0.992164 0.056754\n5027 11.846218 -0.030158 -1.173522 1.176382 0.042775 0.103769 0.992076 0.056454\n5028 11.855534 -0.029242 -1.173140 1.176168 0.047269 0.104489 0.991836 0.055765\n5029 11.862658 -0.028830 -1.172557 1.176037 0.046315 0.106608 0.991668 0.055530\n5030 11.870157 -0.028508 -1.172132 1.175858 0.044765 0.108486 0.991581 0.054725\n5031 11.880437 -0.028213 -1.171569 1.175592 0.042460 0.111270 0.991433 0.053643\n5032 11.887162 -0.027721 -1.170993 1.175529 0.043538 0.112376 0.991281 0.053282\n5033 11.896156 -0.027263 -1.170368 1.175372 0.043764 0.113633 0.991150 0.052857\n5034 11.904637 -0.027148 -1.169745 1.175151 0.044690 0.115196 0.990984 0.051797\n5035 11.912077 -0.026894 -1.169001 1.175048 0.044163 0.116599 0.990864 0.051402\n5036 11.921136 -0.026696 -1.168416 1.174986 0.041330 0.118146 0.990820 0.051081\n5037 11.928764 -0.026653 -1.167632 1.174922 0.040089 0.119765 0.990714 0.050347\n5038 11.936622 -0.026198 -1.167142 1.174719 0.041161 0.121087 0.990546 0.049621\n5039 11.945185 -0.025764 -1.166307 1.174774 0.039932 0.121329 0.990655 0.047820\n5040 11.955134 -0.025443 -1.165709 1.174799 0.037453 0.122485 0.990670 0.046556\n5041 11.961625 -0.025100 -1.165091 1.174910 0.034906 0.122710 0.990816 0.044797\n5042 11.970721 -0.024491 -1.164069 1.174943 0.033543 0.123357 0.990893 0.042288\n5043 11.979030 -0.023930 -1.163616 1.175072 0.030752 0.124064 0.990988 0.040071\n5044 11.986666 -0.023656 -1.162827 1.175137 0.027656 0.125040 0.991066 0.037254\n5045 11.996109 -0.022746 -1.162541 1.175222 0.027434 0.125597 0.991103 0.034469\n5046 12.003899 -0.022501 -1.161359 1.175340 0.019989 0.125210 0.991439 0.031168\n5047 12.012794 -0.021224 -1.160692 1.175458 0.024189 0.123419 0.991660 0.028169\n5048 12.021246 -0.020851 -1.160179 1.175531 0.022397 0.122167 0.991942 0.025013\n5049 12.028605 -0.019908 -1.159885 1.175727 0.023380 0.120218 0.992236 0.021652\n5050 12.036505 -0.019183 -1.159078 1.176081 0.023316 0.119413 0.992400 0.018420\n5051 12.047409 -0.018339 -1.158335 1.176332 0.023438 0.117019 0.992718 0.016367\n5052 12.054774 -0.017934 -1.157739 1.176595 0.023469 0.117007 0.992763 0.013396\n5053 12.062795 -0.017079 -1.157055 1.176818 0.026068 0.116989 0.992730 0.010968\n5054 12.071910 -0.016338 -1.156407 1.177199 0.025532 0.117794 0.992670 0.008900\n5055 12.078391 -0.015726 -1.155701 1.177534 0.023695 0.118426 0.992655 0.007096\n5056 12.088670 -0.014882 -1.155103 1.177865 0.021588 0.120322 0.992482 0.006012\n5057 12.095517 -0.014456 -1.154333 1.178031 0.018226 0.122431 0.992297 0.004987\n5058 12.103188 -0.013241 -1.153774 1.178286 0.018895 0.123574 0.992140 0.005626\n5059 12.111584 -0.012865 -1.152912 1.178423 0.015130 0.126010 0.991898 0.005484\n5060 12.121059 -0.012094 -1.152317 1.178343 0.013955 0.128024 0.991651 0.006616\n5061 12.129130 -0.011964 -1.151183 1.178643 0.005144 0.130514 0.991402 0.007820\n5062 12.136499 -0.011336 -1.150395 1.178837 0.003403 0.132055 0.991185 0.010135\n5063 12.146423 -0.010171 -1.149368 1.178801 0.002971 0.133211 0.991002 0.012672\n5064 12.153686 -0.009478 -1.148401 1.178683 0.002537 0.135374 0.990680 0.014852\n5065 12.163535 -0.009049 -1.148160 1.178938 -0.003260 0.135731 0.990568 0.018462\n5066 12.170331 -0.008504 -1.147229 1.178964 -0.006006 0.137325 0.990261 0.022130\n5067 12.178216 -0.007868 -1.146475 1.179158 -0.008580 0.137942 0.990065 0.025869\n5068 12.186501 -0.007770 -1.145484 1.179414 -0.015242 0.138390 0.989812 0.029800\n5069 12.196284 -0.007343 -1.144607 1.179645 -0.017571 0.138174 0.989680 0.033661\n5070 12.203928 -0.006749 -1.143636 1.180025 -0.017190 0.136932 0.989716 0.037627\n5071 12.212863 -0.006020 -1.142673 1.180440 -0.015623 0.134410 0.989926 0.041668\n5072 12.220271 -0.005266 -1.141710 1.180949 -0.015319 0.131147 0.990198 0.045531\n5073 12.229254 -0.004725 -1.140827 1.181454 -0.015652 0.127674 0.990466 0.049303\n5074 12.237769 -0.003737 -1.140291 1.182074 -0.012324 0.123243 0.990866 0.053334\n5075 12.245852 -0.003240 -1.139372 1.182552 -0.012129 0.119174 0.991151 0.057192\n5076 12.253335 -0.002290 -1.138703 1.183248 -0.006838 0.112921 0.991653 0.061862\n5077 12.261604 -0.001376 -1.138148 1.183658 -0.001042 0.107170 0.992045 0.066030\n5078 12.271316 -0.001366 -1.137078 1.184380 -0.001980 0.101345 0.992372 0.070166\n5079 12.279236 -0.001189 -1.136537 1.184929 -0.000995 0.094793 0.992700 0.074560\n5080 12.286474 0.000079 -1.135986 1.185325 0.006407 0.086770 0.993069 0.079018\n5081 12.294826 0.000259 -1.135261 1.185678 0.007954 0.078614 0.993441 0.082659\n5082 12.303607 0.000231 -1.134232 1.186838 0.006296 0.071666 0.993398 0.089361\n5083 12.312784 0.001182 -1.133602 1.187715 0.008456 0.063177 0.993401 0.095349\n5084 12.319864 0.000987 -1.133166 1.188418 0.008307 0.058266 0.993202 0.100431\n5085 12.330041 0.001604 -1.132456 1.189345 0.010572 0.051947 0.992994 0.105610\n5086 12.337087 0.001975 -1.131925 1.190285 0.010506 0.046680 0.992660 0.111073\n5087 12.346780 0.002696 -1.131376 1.191287 0.014697 0.043357 0.992292 0.115156\n5088 12.353256 0.002884 -1.130893 1.192168 0.015531 0.038347 0.991741 0.121401\n5089 12.361798 0.003585 -1.130843 1.193224 0.018535 0.034933 0.991088 0.127201\n5090 12.371300 0.003566 -1.130317 1.194329 0.020793 0.032242 0.990621 0.131143\n5091 12.379103 0.004282 -1.129966 1.195420 0.027887 0.027914 0.990004 0.135409\n5092 12.386682 0.004199 -1.129593 1.196438 0.029409 0.025801 0.989402 0.139834\n5093 12.397351 0.005237 -1.129608 1.197484 0.039502 0.019921 0.988670 0.143441\n5094 12.403911 0.005626 -1.129176 1.198769 0.044580 0.015312 0.987915 0.147656\n5095 12.412842 0.006717 -1.129172 1.199821 0.054952 0.007575 0.986943 0.151217\n5096 12.420454 0.007325 -1.128894 1.201277 0.060476 0.001141 0.986137 0.154513\n5097 12.429149 0.008231 -1.129072 1.202595 0.069179 -0.005843 0.984976 0.158119\n5098 12.436649 0.008960 -1.128837 1.203987 0.077079 -0.012269 0.983864 0.160999\n5099 12.444728 0.010442 -1.128779 1.205468 0.089764 -0.019338 0.982172 0.164032\n5100 12.455164 0.011399 -1.128611 1.206863 0.099690 -0.025065 0.980610 0.166844\n5101 12.462369 0.012197 -1.128602 1.208230 0.109212 -0.029515 0.978986 0.169669\n5102 12.471291 0.013221 -1.128453 1.209747 0.119261 -0.034546 0.977068 0.172981\n5103 12.479323 0.014455 -1.128517 1.210942 0.132046 -0.040061 0.974663 0.176043\n5104 12.486492 0.015522 -1.128031 1.212574 0.143200 -0.043027 0.972452 0.178828\n5105 12.495058 0.016130 -1.128377 1.214046 0.150720 -0.047872 0.970110 0.184061\n5106 12.505234 0.017625 -1.127996 1.215474 0.161141 -0.052596 0.967588 0.187191\n5107 12.512732 0.018442 -1.128211 1.216865 0.169153 -0.055672 0.965180 0.191611\n5108 12.521403 0.019316 -1.127880 1.218369 0.176890 -0.058921 0.962710 0.196031\n5109 12.528767 0.020138 -1.127426 1.219700 0.185536 -0.062502 0.959977 0.200284\n5110 12.536547 0.021250 -1.127146 1.221280 0.190187 -0.064618 0.957789 0.205652\n5111 12.545989 0.022480 -1.127025 1.222716 0.196221 -0.066623 0.955128 0.211635\n5112 12.553524 0.023172 -1.126203 1.224269 0.200661 -0.068595 0.952890 0.216867\n5113 12.562606 0.024299 -1.125858 1.225950 0.202945 -0.069070 0.950740 0.223913\n5114 12.571370 0.025548 -1.125296 1.227466 0.206805 -0.069691 0.948231 0.230723\n5115 12.579512 0.027011 -1.124990 1.228860 0.211229 -0.069298 0.945415 0.238266\n5116 12.589630 0.028659 -1.124932 1.230162 0.217252 -0.068863 0.942179 0.245678\n5117 12.595566 0.030226 -1.124343 1.231715 0.222266 -0.067986 0.939107 0.253088\n5118 12.603947 0.031857 -1.123765 1.233074 0.230107 -0.066929 0.935282 0.260421\n5119 12.613265 0.033522 -1.123025 1.234286 0.238683 -0.066128 0.931107 0.267763\n5120 12.620701 0.034800 -1.122314 1.235534 0.246931 -0.064383 0.926883 0.275259\n5121 12.629398 0.036438 -1.121314 1.236773 0.255570 -0.062492 0.922582 0.282173\n5122 12.639314 0.037553 -1.120385 1.237557 0.265989 -0.062286 0.917275 0.289789\n5123 12.646148 0.039485 -1.119381 1.238770 0.276375 -0.059515 0.912022 0.297137\n5124 12.654745 0.041099 -1.118602 1.239672 0.283292 -0.057375 0.907510 0.304762\n5125 12.662407 0.042779 -1.117625 1.240759 0.290788 -0.054567 0.902705 0.312391\n5126 12.669995 0.044708 -1.116624 1.241576 0.300385 -0.051065 0.897419 0.319062\n5127 12.679723 0.046381 -1.115971 1.242325 0.306904 -0.047901 0.892752 0.326357\n5128 12.687477 0.048506 -1.115033 1.242842 0.313869 -0.044097 0.888002 0.333157\n5129 12.696340 0.050508 -1.114676 1.243532 0.321001 -0.040928 0.882813 0.340478\n5130 12.703611 0.052533 -1.113705 1.243971 0.327562 -0.037659 0.877876 0.347301\n5131 12.712186 0.054870 -1.113039 1.244191 0.334354 -0.034590 0.872311 0.355083\n5132 12.720195 0.056674 -1.112190 1.244217 0.339767 -0.030911 0.867203 0.362715\n5133 12.729709 0.058798 -1.111424 1.244635 0.345491 -0.029360 0.861835 0.370155\n5134 12.737434 0.061500 -1.111418 1.244394 0.357149 -0.025963 0.853311 0.378986\n5135 12.746195 0.062926 -1.110920 1.244233 0.362925 -0.020518 0.847607 0.386559\n5136 12.753674 0.065518 -1.110359 1.244182 0.371435 -0.017495 0.840881 0.393255\n5137 12.762339 0.068135 -1.109914 1.243898 0.383333 -0.012909 0.832765 0.399239\n5138 12.771046 0.070651 -1.109447 1.243534 0.392397 -0.007588 0.825864 0.404865\n5139 12.779064 0.073062 -1.108952 1.242986 0.401271 -0.002154 0.818854 0.410432\n5140 12.786786 0.075515 -1.108526 1.242420 0.409581 0.002919 0.811942 0.415915\n5141 12.795648 0.077856 -1.108061 1.241782 0.417722 0.007933 0.805349 0.420544\n5142 12.803876 0.080528 -1.107866 1.240868 0.424759 0.011518 0.798280 0.426843\n5143 12.812894 0.082968 -1.107632 1.240144 0.432760 0.016717 0.791121 0.431933\n5144 12.819975 0.085462 -1.107710 1.239059 0.440719 0.020119 0.783433 0.437716\n5145 12.828190 0.088066 -1.107693 1.237923 0.448898 0.022359 0.775188 0.443932\n5146 12.836496 0.090527 -1.107466 1.236731 0.456337 0.025054 0.767110 0.450190\n5147 12.846021 0.093111 -1.107320 1.235484 0.463832 0.028745 0.758621 0.456649\n5148 12.853697 0.095522 -1.107213 1.234260 0.470507 0.032157 0.751395 0.461514\n5149 12.863398 0.098108 -1.106916 1.233112 0.478452 0.035642 0.743540 0.465790\n5150 12.870501 0.100499 -1.106440 1.231882 0.485401 0.040607 0.736178 0.469871\n5151 12.878093 0.102871 -1.105886 1.230617 0.492906 0.045114 0.729077 0.472711\n5152 12.887095 0.105786 -1.105206 1.229091 0.501438 0.050696 0.721209 0.475235\n5153 12.896218 0.108325 -1.104774 1.227687 0.509107 0.055518 0.714139 0.477214\n5154 12.904428 0.110422 -1.104499 1.226804 0.515879 0.060206 0.707288 0.479570\n5155 12.912900 0.112472 -1.104059 1.225807 0.522398 0.064143 0.700827 0.481485\n5156 12.920586 0.114858 -1.103779 1.223971 0.529165 0.066933 0.693820 0.483859\n5157 12.929252 0.116752 -1.102920 1.223434 0.535196 0.069321 0.686950 0.486683\n5158 12.937345 0.118708 -1.102140 1.222522 0.539652 0.072008 0.681676 0.488782\n5159 12.946217 0.120125 -1.101740 1.222025 0.543416 0.073656 0.677476 0.490204\n5160 12.955238 0.121735 -1.100786 1.221185 0.546246 0.077451 0.673478 0.491981\n5161 12.961793 0.123209 -1.099927 1.220473 0.546681 0.078592 0.671030 0.494654\n5162 12.970141 0.124433 -1.099053 1.220167 0.547914 0.082851 0.669204 0.495068\n5163 12.978421 0.125860 -1.097924 1.219750 0.546814 0.083944 0.668329 0.497278\n5164 12.987337 0.126941 -1.096804 1.219609 0.546478 0.088616 0.668141 0.497088\n5165 12.996163 0.127990 -1.095507 1.219455 0.542819 0.089124 0.669505 0.499166\n5166 13.003329 0.128964 -1.094313 1.219520 0.538848 0.091337 0.672136 0.499533\n5167 13.012960 0.129886 -1.092963 1.219627 0.534836 0.093216 0.675018 0.499612\n5168 13.020334 0.130790 -1.091670 1.219909 0.530256 0.095044 0.678796 0.499031\n5169 13.030188 0.131250 -1.090376 1.220543 0.524215 0.095665 0.683769 0.498506\n5170 13.037315 0.131550 -1.089138 1.221385 0.518507 0.096875 0.690881 0.494418\n5171 13.045863 0.131930 -1.087524 1.221656 0.512119 0.095590 0.696276 0.493758\n5172 13.054858 0.131627 -1.085806 1.222376 0.504499 0.094491 0.704081 0.490736\n5173 13.063172 0.131743 -1.084487 1.223200 0.497342 0.093830 0.711194 0.487903\n5174 13.070996 0.131451 -1.082783 1.223924 0.488846 0.093689 0.719281 0.484652\n5175 13.079186 0.131346 -1.080994 1.224866 0.481618 0.092448 0.726743 0.480981\n5176 13.086787 0.130611 -1.079238 1.226024 0.473077 0.091041 0.735062 0.477067\n5177 13.094803 0.129774 -1.077773 1.227058 0.463699 0.092065 0.744174 0.471923\n5178 13.104923 0.128734 -1.076335 1.228303 0.454515 0.092176 0.753234 0.466432\n5179 13.112689 0.127730 -1.074577 1.229721 0.446337 0.092541 0.761563 0.460696\n5180 13.121190 0.126333 -1.072637 1.231345 0.437868 0.093013 0.770027 0.454618\n5181 13.128598 0.124698 -1.070650 1.232887 0.428068 0.092947 0.779840 0.447178\n5182 13.136567 0.122767 -1.069356 1.234427 0.417449 0.092681 0.789359 0.440522\n5183 13.145967 0.120692 -1.067424 1.236194 0.408344 0.091817 0.798191 0.433262\n5184 13.153476 0.118589 -1.065860 1.238044 0.398039 0.089936 0.807556 0.425829\n5185 13.161352 0.116137 -1.063681 1.239750 0.386725 0.087895 0.817500 0.417626\n5186 13.172625 0.113454 -1.062279 1.241456 0.375188 0.085073 0.827128 0.409702\n5187 13.179742 0.110652 -1.060672 1.243278 0.362285 0.083859 0.836737 0.401981\n5188 13.186643 0.107609 -1.058864 1.244824 0.348657 0.081445 0.847054 0.392815\n5189 13.196186 0.104250 -1.058158 1.246399 0.334366 0.080609 0.857207 0.383274\n5190 13.204688 0.100782 -1.056574 1.248410 0.314473 0.078033 0.869244 0.373406\n5191 13.213385 0.098213 -1.055708 1.249556 0.309899 0.078033 0.875180 0.363228\n5192 13.220532 0.094700 -1.054846 1.250800 0.296740 0.078419 0.884138 0.352271\n5193 13.228016 0.091199 -1.053608 1.252043 0.282015 0.079452 0.893409 0.340551\n5194 13.237338 0.087082 -1.052947 1.253886 0.264418 0.079671 0.902747 0.329823\n5195 13.245135 0.083269 -1.052493 1.255537 0.250423 0.079304 0.910794 0.318516\n5196 13.255213 0.079626 -1.052071 1.256371 0.234423 0.077435 0.919029 0.307303\n5197 13.262543 0.075954 -1.051390 1.257731 0.216325 0.082162 0.926731 0.296011\n5198 13.270294 0.071804 -1.051443 1.259073 0.200724 0.074426 0.933782 0.286743\n5199 13.278015 0.067762 -1.051746 1.260218 0.183630 0.070702 0.940554 0.276839\n5200 13.288339 0.063704 -1.052005 1.261157 0.167576 0.066757 0.946519 0.267513\n5201 13.296205 0.059266 -1.052311 1.261998 0.151556 0.062126 0.951839 0.259181\n5202 13.303246 0.055361 -1.052875 1.262667 0.136463 0.056110 0.956711 0.250866\n5203 13.313408 0.051025 -1.053438 1.263221 0.123270 0.050502 0.960779 0.243223\n5204 13.320365 0.046755 -1.054378 1.263719 0.109233 0.044683 0.964529 0.236127\n5205 13.330165 0.042123 -1.054941 1.264179 0.091199 0.039557 0.968419 0.228654\n5206 13.336958 0.038005 -1.055901 1.264444 0.079112 0.032433 0.971314 0.221898\n5207 13.344685 0.034132 -1.057069 1.264570 0.068306 0.026285 0.973935 0.214694\n5208 13.354454 0.029804 -1.058326 1.264498 0.052474 0.021622 0.976480 0.208003\n5209 13.362052 0.026106 -1.059875 1.264385 0.040643 0.014893 0.978632 0.201013\n5210 13.370590 0.021759 -1.060946 1.264107 0.026240 0.009695 0.980602 0.194004\n5211 13.379378 0.017944 -1.062466 1.263811 0.014277 0.002640 0.982127 0.187660\n5212 13.386674 0.013697 -1.063818 1.263114 -0.001232 -0.002854 0.983489 0.180943\n5213 13.395992 0.009927 -1.065158 1.262464 -0.012343 -0.009460 0.984411 0.175193\n5214 13.404395 0.005140 -1.067066 1.261422 -0.028268 -0.013268 0.985255 0.168218\n5215 13.412738 0.000927 -1.068383 1.260380 -0.041616 -0.019913 0.985576 0.162822\n5216 13.419975 -0.003258 -1.070317 1.259129 -0.055884 -0.027102 0.985634 0.157064\n5217 13.427908 -0.007635 -1.072357 1.257758 -0.069977 -0.031882 0.985179 0.153323\n5218 13.437585 -0.011925 -1.074089 1.256229 -0.083414 -0.039024 0.984629 0.148408\n5219 13.445447 -0.016107 -1.076390 1.254680 -0.096172 -0.046851 0.983715 0.144435\n5220 13.455062 -0.020443 -1.078510 1.252980 -0.109466 -0.053734 0.982490 0.140869\n5221 13.461942 -0.024680 -1.080417 1.251263 -0.120226 -0.062646 0.981191 0.137421\n5222 13.470121 -0.028617 -1.082208 1.249453 -0.131436 -0.069835 0.979831 0.133337\n5223 13.478430 -0.033175 -1.084325 1.247454 -0.143977 -0.075790 0.978067 0.130046\n5224 13.487098 -0.037196 -1.086316 1.245355 -0.153361 -0.083118 0.976277 0.128281\n5225 13.496113 -0.041687 -1.087534 1.243544 -0.166739 -0.087846 0.973980 0.125873\n5226 13.503145 -0.045315 -1.089784 1.241572 -0.175036 -0.094046 0.972439 0.121980\n5227 13.512532 -0.049462 -1.091690 1.239527 -0.183490 -0.099380 0.970666 0.119430\n5228 13.520651 -0.053886 -1.093418 1.237449 -0.191266 -0.103768 0.968672 0.119686\n5229 13.529306 -0.057821 -1.095128 1.235353 -0.199174 -0.110908 0.966641 0.116768\n5230 13.538652 -0.061435 -1.096957 1.233124 -0.204516 -0.116899 0.964936 0.115787\n5231 13.545456 -0.065703 -1.098376 1.231298 -0.211737 -0.123435 0.962709 0.114551\n5232 13.553387 -0.069750 -1.100014 1.229050 -0.218221 -0.128899 0.960595 0.114112\n5233 13.562851 -0.073355 -1.101279 1.227064 -0.222208 -0.135227 0.959016 0.112361\n5234 13.571046 -0.077581 -1.102400 1.225012 -0.229270 -0.139791 0.956559 0.113527\n5235 13.579345 -0.081611 -1.103452 1.222923 -0.235639 -0.145064 0.954438 0.111708\n5236 13.588261 -0.085054 -1.104592 1.220818 -0.239713 -0.150037 0.952624 0.111960\n5237 13.595964 -0.089054 -1.105570 1.218650 -0.246287 -0.153816 0.950402 0.111444\n5238 13.605385 -0.092670 -1.106429 1.216573 -0.251922 -0.157836 0.948025 0.113456\n5239 13.611809 -0.096749 -1.107257 1.214337 -0.258165 -0.161021 0.945473 0.116211\n5240 13.619903 -0.100418 -1.108055 1.212168 -0.264642 -0.164880 0.942655 0.119085\n5241 13.628514 -0.103515 -1.108998 1.209993 -0.268909 -0.168936 0.940408 0.121577\n5242 13.637463 -0.107346 -1.109213 1.208081 -0.272475 -0.173234 0.937990 0.126187\n5243 13.646052 -0.110385 -1.110203 1.205933 -0.277968 -0.176174 0.935088 0.131560\n5244 13.653179 -0.113289 -1.110944 1.204014 -0.282493 -0.179508 0.932313 0.136997\n5245 13.662480 -0.115924 -1.111409 1.202176 -0.286310 -0.183953 0.929232 0.143931\n5246 13.671310 -0.118525 -1.111996 1.200720 -0.287406 -0.187454 0.927105 0.150783\n5247 13.680939 -0.120720 -1.112895 1.199130 -0.290184 -0.190350 0.924456 0.157925\n5248 13.687375 -0.122732 -1.113275 1.197966 -0.291209 -0.192752 0.922413 0.164919\n5249 13.695519 -0.124837 -1.113762 1.196614 -0.292500 -0.195492 0.920015 0.172623\n5250 13.704041 -0.126601 -1.113877 1.195291 -0.293457 -0.199287 0.917474 0.180027\n5251 13.712565 -0.128169 -1.114061 1.194217 -0.294061 -0.201314 0.915405 0.187178\n5252 13.719985 -0.129668 -1.114276 1.193262 -0.295506 -0.201422 0.913471 0.194104\n5253 13.729975 -0.130692 -1.114156 1.192736 -0.296014 -0.203987 0.911394 0.200313\n5254 13.736837 -0.132169 -1.113989 1.192456 -0.297382 -0.201636 0.910051 0.206674\n5255 13.745795 -0.133346 -1.113871 1.192179 -0.296853 -0.200737 0.909149 0.212207\n5256 13.753931 -0.134352 -1.113153 1.192127 -0.295887 -0.199517 0.908716 0.216515\n5257 13.763100 -0.135264 -1.112855 1.192206 -0.294534 -0.197566 0.908566 0.220738\n5258 13.770924 -0.135887 -1.111800 1.192543 -0.293308 -0.194561 0.908831 0.223927\n5259 13.779169 -0.136522 -1.111465 1.192998 -0.292044 -0.192559 0.908957 0.226779\n5260 13.786375 -0.136856 -1.110737 1.193637 -0.288987 -0.191218 0.909738 0.228689\n5261 13.794724 -0.137044 -1.109394 1.194534 -0.288500 -0.187096 0.910361 0.230230\n5262 13.804370 -0.136752 -1.108333 1.195657 -0.283490 -0.186893 0.911739 0.231162\n5263 13.812594 -0.136471 -1.106946 1.196840 -0.281293 -0.183135 0.912841 0.232502\n5264 13.819705 -0.136142 -1.105640 1.198329 -0.277758 -0.179699 0.914515 0.232855\n5265 13.830112 -0.136163 -1.104618 1.199780 -0.273293 -0.175301 0.916609 0.233256\n5266 13.836588 -0.135094 -1.102993 1.201503 -0.270455 -0.169887 0.918246 0.234131\n5267 13.844614 -0.134356 -1.101524 1.203926 -0.261885 -0.163778 0.921655 0.234830\n5268 13.854717 -0.133332 -1.099525 1.206380 -0.256041 -0.156880 0.924323 0.235496\n5269 13.862782 -0.132083 -1.097526 1.208816 -0.251194 -0.149105 0.926519 0.237133\n5270 13.872761 -0.130310 -1.096077 1.211225 -0.244043 -0.142865 0.929075 0.238439\n5271 13.880166 -0.129086 -1.093757 1.213982 -0.240218 -0.131616 0.931866 0.237904\n5272 13.887480 -0.127115 -1.091466 1.216716 -0.233482 -0.123781 0.934857 0.237079\n5273 13.896913 -0.124583 -1.089323 1.219672 -0.225016 -0.114467 0.937939 0.237771\n5274 13.903768 -0.122870 -1.085935 1.222646 -0.216011 -0.105305 0.941858 0.234851\n5275 13.911181 -0.120448 -1.083137 1.226044 -0.206268 -0.094881 0.945350 0.234020\n5276 13.920676 -0.118073 -1.079982 1.229217 -0.198512 -0.084474 0.948352 0.232562\n5277 13.928812 -0.115604 -1.076452 1.232398 -0.190535 -0.072664 0.951324 0.231081\n5278 13.937655 -0.112938 -1.073029 1.235687 -0.182785 -0.060659 0.953946 0.229993\n5279 13.946230 -0.110025 -1.069248 1.239240 -0.176661 -0.045856 0.956528 0.227467\n5280 13.953972 -0.106887 -1.065450 1.242034 -0.167354 -0.034681 0.958985 0.226136\n5281 13.963095 -0.103270 -1.061596 1.245182 -0.161858 -0.019193 0.960687 0.224755\n5282 13.970505 -0.099764 -1.057120 1.248537 -0.153984 -0.003251 0.962478 0.223418\n5283 13.979726 -0.095456 -1.052936 1.252150 -0.140607 0.012290 0.964552 0.222978\n5284 13.987657 -0.092085 -1.049076 1.255045 -0.135572 0.030196 0.965701 0.219385\n5285 13.995775 -0.087861 -1.044597 1.258486 -0.125155 0.043344 0.966745 0.218771\n5286 14.004761 -0.083079 -1.040559 1.261747 -0.113230 0.058470 0.968083 0.215813\n5287 14.012756 -0.078633 -1.036047 1.264535 -0.100404 0.074003 0.968446 0.215768\n5288 14.020159 -0.073942 -1.032120 1.267771 -0.089312 0.088196 0.968844 0.213511\n5289 14.029421 -0.069090 -1.027996 1.270692 -0.078924 0.104390 0.968535 0.211691\n5290 14.037298 -0.064476 -1.023345 1.273425 -0.070248 0.119770 0.967640 0.210695\n5291 14.046147 -0.059068 -1.019105 1.276202 -0.055932 0.132269 0.967033 0.210296\n5292 14.054500 -0.054452 -1.014692 1.278575 -0.044751 0.146545 0.965785 0.209241\n5293 14.062386 -0.048916 -1.010473 1.280911 -0.030231 0.160508 0.964108 0.209330\n5294 14.071883 -0.043362 -1.006021 1.283168 -0.013712 0.177444 0.961735 0.208306\n5295 14.079419 -0.038860 -1.001576 1.285029 -0.006273 0.187049 0.959416 0.210936\n5296 14.087172 -0.032419 -0.997453 1.286674 0.009174 0.201590 0.956348 0.211368\n5297 14.096069 -0.027321 -0.993041 1.287978 0.023416 0.214745 0.953058 0.212170\n5298 14.104707 -0.021546 -0.988555 1.289590 0.037125 0.229937 0.949141 0.211852\n5299 14.113155 -0.016246 -0.983978 1.290915 0.040794 0.241572 0.945798 0.213178\n5300 14.121542 -0.009994 -0.979802 1.291426 0.058187 0.258681 0.939662 0.216180\n5301 14.129367 -0.005314 -0.975244 1.292352 0.070316 0.274048 0.934703 0.215137\n5302 14.136301 0.000271 -0.970720 1.292951 0.084974 0.290804 0.928291 0.215609\n5303 14.146031 0.005519 -0.965889 1.292419 0.095389 0.309127 0.921678 0.214129\n5304 14.154099 0.011199 -0.961875 1.292962 0.109660 0.324282 0.915272 0.212350\n5305 14.162764 0.016483 -0.957835 1.292569 0.121066 0.341897 0.907321 0.212644\n5306 14.171181 0.022014 -0.953460 1.292032 0.133367 0.358581 0.899426 0.211342\n5307 14.179098 0.027564 -0.949251 1.290954 0.145329 0.373149 0.891599 0.211404\n5308 14.187119 0.032270 -0.944754 1.290326 0.161412 0.386782 0.883230 0.210360\n5309 14.196008 0.037214 -0.941373 1.288969 0.169192 0.399904 0.875731 0.211061\n5310 14.204261 0.043160 -0.936813 1.286699 0.184201 0.411500 0.867468 0.210326\n5311 14.212750 0.046982 -0.933406 1.286567 0.195393 0.423436 0.858789 0.212144\n5312 14.221077 0.052407 -0.930422 1.285158 0.209035 0.433552 0.849863 0.214639\n5313 14.229214 0.056984 -0.926981 1.283532 0.218544 0.445418 0.841098 0.215396\n5314 14.237737 0.061520 -0.924177 1.282104 0.228841 0.454590 0.832781 0.217844\n5315 14.246014 0.066159 -0.921565 1.280379 0.237618 0.463870 0.825448 0.216791\n5316 14.253452 0.070046 -0.918434 1.277966 0.247407 0.471921 0.817904 0.217056\n5317 14.262755 0.074053 -0.916663 1.276760 0.255807 0.479531 0.810304 0.219136\n5318 14.270651 0.078232 -0.914479 1.275061 0.263763 0.486763 0.803275 0.219635\n5319 14.278316 0.081880 -0.912511 1.272990 0.271062 0.493166 0.797002 0.219318\n5320 14.286658 0.085452 -0.910292 1.271138 0.279184 0.498708 0.790462 0.220264\n5321 14.295966 0.088693 -0.908641 1.269578 0.285703 0.503548 0.785108 0.220040\n5322 14.304363 0.091378 -0.907180 1.267899 0.292011 0.508891 0.779481 0.219473\n5323 14.312655 0.094451 -0.905210 1.266147 0.298217 0.513659 0.773738 0.220342\n5324 14.321192 0.097365 -0.904064 1.264800 0.302455 0.516850 0.770357 0.218944\n5325 14.329919 0.099823 -0.902885 1.263252 0.305790 0.520687 0.766858 0.217500\n5326 14.336876 0.102421 -0.901904 1.261757 0.308662 0.523888 0.763868 0.216278\n5327 14.345473 0.105025 -0.901018 1.260763 0.313175 0.526085 0.760572 0.216071\n5328 14.354157 0.107560 -0.900743 1.258545 0.318913 0.526145 0.758456 0.214966\n5329 14.362678 0.109106 -0.899105 1.257918 0.318229 0.530095 0.756349 0.213695\n5330 14.371796 0.110893 -0.898420 1.256497 0.319221 0.532057 0.755220 0.211321\n5331 14.379892 0.112827 -0.897595 1.255270 0.322357 0.534276 0.752532 0.210549\n5332 14.387810 0.114539 -0.896680 1.254096 0.324431 0.536696 0.750239 0.209388\n5333 14.395847 0.116351 -0.895786 1.252677 0.325440 0.537794 0.749287 0.208410\n5334 14.404132 0.117560 -0.895222 1.252287 0.325628 0.540981 0.746911 0.208399\n5335 14.412294 0.118876 -0.894976 1.251482 0.328581 0.541523 0.744958 0.209345\n5336 14.419865 0.120488 -0.894509 1.250656 0.329772 0.543187 0.743038 0.209984\n5337 14.429865 0.122015 -0.893987 1.249279 0.331602 0.543286 0.741551 0.212092\n5338 14.437786 0.122948 -0.893904 1.249048 0.331652 0.543605 0.740832 0.213703\n5339 14.445924 0.123885 -0.893897 1.248072 0.334974 0.542456 0.739084 0.217459\n5340 14.453991 0.125335 -0.893564 1.247482 0.334255 0.542524 0.738602 0.220020\n5341 14.462614 0.126195 -0.893249 1.246990 0.335758 0.542190 0.737014 0.223844\n5342 14.469998 0.126917 -0.893339 1.246663 0.336140 0.541715 0.736420 0.226363\n5343 14.478133 0.127966 -0.893460 1.246009 0.338516 0.540499 0.734747 0.231115\n5344 14.489667 0.128420 -0.893670 1.245623 0.339242 0.539029 0.734565 0.234046\n5345 14.495656 0.128492 -0.893979 1.245802 0.339558 0.536939 0.735471 0.235542\n5346 14.504266 0.129194 -0.894182 1.245429 0.339130 0.534966 0.735663 0.240004\n5347 14.512352 0.129361 -0.894639 1.245316 0.340662 0.532893 0.735304 0.243519\n5348 14.520060 0.129407 -0.895224 1.245674 0.340957 0.530373 0.735818 0.247032\n5349 14.530032 0.128706 -0.895892 1.246482 0.339088 0.527720 0.737679 0.249723\n5350 14.537355 0.127939 -0.896402 1.247078 0.336239 0.524453 0.740479 0.252160\n5351 14.544703 0.127058 -0.896983 1.248371 0.336405 0.519709 0.742365 0.256180\n5352 14.554512 0.125898 -0.898000 1.249268 0.332710 0.515149 0.746195 0.259073\n5353 14.562843 0.124672 -0.899097 1.250623 0.330687 0.509395 0.749504 0.263452\n5354 14.570425 0.123035 -0.900283 1.251751 0.326416 0.502706 0.754939 0.266095\n5355 14.579291 0.120656 -0.901430 1.253598 0.320164 0.496968 0.760729 0.267973\n5356 14.587888 0.118558 -0.902910 1.255219 0.313077 0.490412 0.767084 0.270297\n5357 14.596062 0.116167 -0.904688 1.256970 0.307266 0.482029 0.774057 0.272161\n5358 14.603322 0.113564 -0.906406 1.259060 0.301407 0.473642 0.779855 0.276845\n5359 14.612931 0.110292 -0.908732 1.260926 0.291782 0.464120 0.788706 0.278205\n5360 14.621292 0.107190 -0.911134 1.263152 0.285106 0.453430 0.795952 0.282093\n5361 14.628919 0.103576 -0.913555 1.265469 0.276487 0.442407 0.803968 0.285423\n5362 14.636538 0.099333 -0.916106 1.267337 0.266156 0.431908 0.812792 0.286330\n5363 14.644688 0.095804 -0.918881 1.269368 0.256798 0.420032 0.820832 0.289593\n5364 14.655315 0.091589 -0.922036 1.271110 0.247117 0.407986 0.829511 0.290503\n5365 14.662537 0.087671 -0.925023 1.272996 0.237045 0.397789 0.836715 0.292374\n5366 14.671206 0.083056 -0.928126 1.274586 0.226015 0.387405 0.844590 0.292409\n5367 14.678864 0.078716 -0.931631 1.275935 0.217951 0.374940 0.852075 0.293062\n5368 14.686904 0.073932 -0.935199 1.277724 0.206254 0.363319 0.860016 0.292969\n5369 14.697016 0.069064 -0.938932 1.278764 0.197065 0.350612 0.867315 0.293260\n5370 14.704712 0.064380 -0.942549 1.280180 0.189406 0.335757 0.874592 0.294078\n5371 14.713550 0.060054 -0.946773 1.281490 0.182010 0.319640 0.882120 0.294223\n5372 14.720392 0.054575 -0.950839 1.282144 0.171146 0.306006 0.889195 0.293941\n5373 14.728051 0.050047 -0.954954 1.283125 0.161223 0.289064 0.896576 0.294280\n5374 14.736463 0.045078 -0.959202 1.283736 0.152018 0.272267 0.903018 0.295498\n5375 14.745550 0.040563 -0.963442 1.284445 0.142023 0.258504 0.909034 0.294385\n5376 14.754773 0.036148 -0.967578 1.284700 0.133456 0.240134 0.915193 0.294868\n5377 14.762630 0.031794 -0.971268 1.284510 0.122886 0.224984 0.920771 0.294045\n5378 14.770410 0.025569 -0.974921 1.285367 0.111214 0.210000 0.925384 0.295290\n5379 14.779298 0.022806 -0.979367 1.285182 0.102048 0.192152 0.931145 0.292632\n5380 14.788244 0.018558 -0.982983 1.284700 0.099327 0.179572 0.933768 0.293198\n5381 14.794737 0.014234 -0.986717 1.284409 0.091657 0.165535 0.937040 0.293520\n5382 14.803424 0.009798 -0.990499 1.284132 0.081170 0.150724 0.940876 0.292312\n5383 14.812476 0.005558 -0.993672 1.283529 0.073430 0.137408 0.943590 0.292173\n5384 14.820309 0.001423 -0.997098 1.282978 0.064960 0.124119 0.946028 0.292242\n5385 14.829712 -0.002228 -1.000191 1.282305 0.061175 0.111092 0.947507 0.293506\n5386 14.837243 -0.006216 -1.003193 1.281495 0.053103 0.097189 0.949980 0.292015\n5387 14.846332 -0.009757 -1.006476 1.280833 0.044181 0.083039 0.951120 0.294148\n5388 14.853717 -0.013436 -1.009062 1.280299 0.034076 0.068242 0.952984 0.293263\n5389 14.862041 -0.016539 -1.011914 1.279514 0.029096 0.056050 0.953426 0.294940\n5390 14.871198 -0.019971 -1.014417 1.278723 0.022629 0.041116 0.954576 0.294248\n5391 14.879888 -0.023328 -1.017344 1.278010 0.015101 0.029404 0.954380 0.296759\n5392 14.887637 -0.026655 -1.019643 1.277212 0.006688 0.014431 0.955249 0.295376\n5393 14.896134 -0.029464 -1.021894 1.276246 -0.000476 0.003537 0.955090 0.296293\n5394 14.903025 -0.031698 -1.024730 1.275499 -0.002803 -0.008438 0.954283 0.298772\n5395 14.912090 -0.034827 -1.026360 1.274537 -0.008831 -0.021492 0.954068 0.298689\n5396 14.921145 -0.037328 -1.028541 1.273803 -0.014326 -0.031501 0.953046 0.300844\n5397 14.929925 -0.040276 -1.030754 1.272947 -0.020828 -0.040312 0.952159 0.302216\n5398 14.937121 -0.042050 -1.032099 1.272271 -0.023078 -0.048920 0.950981 0.304481\n5399 14.945782 -0.045070 -1.033520 1.271457 -0.030773 -0.055041 0.949406 0.307655\n5400 14.954584 -0.047232 -1.035681 1.270876 -0.033706 -0.061186 0.948218 0.309845\n5401 14.962777 -0.048908 -1.036180 1.270446 -0.033108 -0.067046 0.947025 0.312335\n5402 14.970454 -0.050823 -1.037012 1.269862 -0.036275 -0.069915 0.945803 0.315043\n5403 14.978571 -0.052634 -1.038007 1.269341 -0.038549 -0.073047 0.944667 0.317461\n5404 14.987308 -0.054360 -1.038579 1.268928 -0.040437 -0.075816 0.943440 0.320216\n5405 14.995967 -0.056028 -1.038900 1.268664 -0.041590 -0.079514 0.942091 0.323128\n5406 15.003703 -0.057379 -1.039482 1.268281 -0.043207 -0.081110 0.940689 0.326587\n5407 15.012690 -0.058568 -1.039819 1.268066 -0.043483 -0.084134 0.939037 0.330516\n5408 15.020668 -0.059609 -1.040313 1.267925 -0.042957 -0.086442 0.937415 0.334569\n5409 15.030053 -0.060352 -1.040780 1.267680 -0.041597 -0.089582 0.935448 0.339385\n5410 15.037587 -0.061247 -1.040957 1.267627 -0.041641 -0.088937 0.933723 0.344264\n5411 15.044653 -0.061751 -1.041081 1.267609 -0.041756 -0.092077 0.931770 0.348689\n5412 15.053515 -0.061723 -1.041699 1.267173 -0.039420 -0.091523 0.930145 0.353412\n5413 15.062877 -0.063233 -1.040917 1.267437 -0.039852 -0.090439 0.928210 0.358691\n5414 15.071226 -0.063220 -1.041014 1.267221 -0.034617 -0.090009 0.925013 0.367493\n5415 15.079660 -0.063346 -1.041293 1.267537 -0.031494 -0.090383 0.923105 0.372446\n5416 15.086449 -0.063284 -1.040700 1.267971 -0.027696 -0.087307 0.920467 0.379936\n5417 15.094711 -0.063988 -1.039506 1.267851 -0.030047 -0.084843 0.918725 0.384505\n5418 15.104613 -0.063502 -1.039244 1.268175 -0.026726 -0.083014 0.914762 0.394468\n5419 15.111809 -0.063023 -1.038416 1.268626 -0.022185 -0.080270 0.911620 0.402510\n5420 15.120988 -0.063197 -1.037124 1.268921 -0.018346 -0.071739 0.907870 0.412661\n5421 15.128727 -0.062421 -1.035889 1.269376 -0.013891 -0.067994 0.903623 0.422670\n5422 15.136193 -0.061882 -1.034721 1.269785 -0.011483 -0.060387 0.898581 0.434482\n5423 15.146749 -0.061030 -1.033862 1.270304 -0.005839 -0.054607 0.893714 0.445263\n5424 15.154116 -0.060105 -1.032480 1.270757 -0.001411 -0.045818 0.888063 0.457430\n5425 15.162640 -0.059095 -1.031332 1.271268 0.005025 -0.036954 0.882491 0.468848\n5426 15.169998 -0.057983 -1.030287 1.271906 0.012574 -0.027090 0.876614 0.480267\n5427 15.178580 -0.056867 -1.029344 1.272638 0.021367 -0.018508 0.870840 0.490754\n5428 15.187801 -0.055452 -1.028357 1.273173 0.029310 -0.008629 0.864614 0.501507\n5429 15.195862 -0.053552 -1.027519 1.273883 0.039891 -0.000674 0.858481 0.511291\n5430 15.204575 -0.051482 -1.026432 1.274664 0.052174 0.007095 0.852017 0.520860\n5431 15.212686 -0.049513 -1.025525 1.275600 0.063196 0.015182 0.845751 0.529604\n5432 15.220442 -0.047074 -1.024926 1.276387 0.075620 0.022026 0.838960 0.538463\n5433 15.228321 -0.044482 -1.023545 1.276965 0.087728 0.028035 0.832740 0.545951\n5434 15.239937 -0.041738 -1.022612 1.277707 0.102030 0.035572 0.825515 0.553940\n5435 15.245392 -0.039086 -1.021545 1.278251 0.116148 0.043334 0.817956 0.561765\n5436 15.253361 -0.036733 -1.020860 1.278802 0.129452 0.051611 0.810267 0.569250\n5437 15.262974 -0.034238 -1.020289 1.279210 0.144398 0.059492 0.802433 0.575944\n5438 15.270947 -0.031549 -1.019481 1.279798 0.157160 0.067570 0.794392 0.582818\n5439 15.278059 -0.029195 -1.018650 1.280210 0.170382 0.075213 0.786418 0.588949\n5440 15.288430 -0.026489 -1.017797 1.280463 0.183241 0.081724 0.778900 0.594188\n5441 15.295674 -0.024249 -1.017103 1.280488 0.197137 0.089057 0.770936 0.599052\n5442 15.303014 -0.021618 -1.016327 1.281258 0.207154 0.097628 0.763625 0.603682\n5443 15.312603 -0.019478 -1.015539 1.281734 0.220917 0.104892 0.755222 0.608139\n5444 15.321480 -0.016765 -1.014509 1.281732 0.231769 0.111850 0.748020 0.611751\n5445 15.329135 -0.014407 -1.014009 1.282230 0.242576 0.120169 0.740209 0.615472\n5446 15.336172 -0.012051 -1.013099 1.282477 0.252369 0.126316 0.733895 0.617861\n5447 15.345268 -0.009243 -1.012729 1.282804 0.263599 0.133349 0.727597 0.619141\n5448 15.355569 -0.006952 -1.011540 1.282509 0.277450 0.139304 0.722433 0.617824\n5449 15.363109 -0.004261 -1.010967 1.282518 0.288857 0.144818 0.717403 0.617190\n5450 15.371182 -0.001695 -1.010669 1.282902 0.298659 0.150372 0.712406 0.616984\n5451 15.379345 0.000660 -1.010970 1.283139 0.308139 0.154277 0.708088 0.616328\n5452 15.387248 0.003597 -1.010440 1.283028 0.319978 0.158522 0.704571 0.613242\n5453 15.394620 0.006641 -1.010713 1.283016 0.331349 0.161329 0.698716 0.613170\n5454 15.405618 0.009368 -1.011377 1.282987 0.345938 0.164069 0.693782 0.609979\n5455 15.412039 0.012319 -1.011226 1.282476 0.360396 0.168098 0.686668 0.608560\n5456 15.421475 0.014998 -1.011626 1.282176 0.373526 0.171484 0.680995 0.606067\n5457 15.429019 0.017497 -1.012057 1.281870 0.386760 0.174667 0.674033 0.604639\n5458 15.436641 0.020004 -1.012499 1.281463 0.400166 0.176330 0.667812 0.602330\n5459 15.444574 0.022159 -1.013087 1.281035 0.413452 0.177520 0.661323 0.600163\n5460 15.454713 0.024276 -1.013431 1.280546 0.425871 0.176569 0.655400 0.598254\n5461 15.461922 0.026453 -1.014068 1.280037 0.440227 0.176502 0.648849 0.595014\n5462 15.471242 0.028443 -1.014645 1.279608 0.452947 0.175382 0.642593 0.592583\n5463 15.479238 0.030203 -1.015244 1.279059 0.466700 0.172703 0.635499 0.590344\n5464 15.486927 0.032285 -1.016006 1.278441 0.479473 0.171142 0.629217 0.587283\n5465 15.496761 0.034115 -1.016766 1.277904 0.492977 0.168879 0.621825 0.584625\n5466 15.504479 0.035867 -1.017507 1.277291 0.506835 0.166556 0.613963 0.581745\n5467 15.513307 0.037493 -1.018157 1.276498 0.521129 0.163615 0.605537 0.578774\n5468 15.520905 0.039243 -1.018993 1.275762 0.535043 0.161185 0.597191 0.575424\n5469 15.528668 0.040637 -1.019455 1.274929 0.548243 0.156459 0.588413 0.573341\n5470 15.537322 0.042180 -1.020353 1.273929 0.561960 0.152760 0.579909 0.569712\n5471 15.545715 0.043938 -1.021095 1.273277 0.575598 0.150164 0.571424 0.565343\n5472 15.554668 0.044947 -1.021585 1.272303 0.589329 0.144825 0.563156 0.560868\n5473 15.563106 0.046242 -1.022591 1.271392 0.601949 0.141719 0.555293 0.556078\n5474 15.571049 0.047467 -1.023112 1.270605 0.614671 0.137246 0.547673 0.550815\n5475 15.579186 0.048726 -1.023577 1.269874 0.627034 0.132765 0.540189 0.545342\n5476 15.587188 0.049847 -1.024041 1.268775 0.639290 0.127893 0.532886 0.539429\n5477 15.595016 0.050860 -1.024561 1.267933 0.650360 0.123425 0.526322 0.533651\n5478 15.605300 0.051859 -1.025059 1.266448 0.660806 0.118003 0.520707 0.527518\n5479 15.613136 0.052923 -1.025392 1.265542 0.670510 0.114230 0.515325 0.521352\n5480 15.620413 0.053890 -1.026016 1.264348 0.679217 0.109332 0.511681 0.514677\n5481 15.630044 0.055048 -1.026573 1.263153 0.687489 0.104871 0.508619 0.507610\n5482 15.637526 0.056077 -1.027075 1.261904 -0.695391 -0.099859 -0.506229 -0.500191\n5483 15.645879 0.056931 -1.027414 1.260627 -0.703618 -0.094730 -0.503909 -0.491959\n5484 15.655305 0.057922 -1.027636 1.259572 -0.711455 -0.089490 -0.501965 -0.483585\n5485 15.662666 0.058750 -1.027907 1.258257 -0.719579 -0.083732 -0.500316 -0.474214\n5486 15.671699 0.059837 -1.027501 1.256751 -0.728368 -0.077530 -0.498114 -0.464060\n5487 15.678968 0.060465 -1.028298 1.255867 -0.735446 -0.072641 -0.496757 -0.455056\n5488 15.687542 0.060770 -1.028470 1.254412 -0.743622 -0.067160 -0.494359 -0.445112\n5489 15.695735 0.061933 -1.028767 1.253263 -0.750484 -0.061596 -0.493400 -0.435358\n5490 15.704993 0.062726 -1.028224 1.251650 -0.758644 -0.058043 -0.491610 -0.423569\n5491 15.712307 0.063400 -1.028442 1.250185 -0.765415 -0.053266 -0.491395 -0.412108\n5492 15.721632 0.064426 -1.028341 1.248676 -0.773120 -0.051667 -0.488589 -0.401121\n5493 15.729289 0.065223 -1.028280 1.246993 -0.780614 -0.048687 -0.487703 -0.387837\n5494 15.737598 0.066113 -1.028119 1.245171 -0.788633 -0.046326 -0.485458 -0.374490\n5495 15.745453 0.066967 -1.027999 1.243090 -0.796097 -0.043801 -0.483837 -0.360851\n5496 15.754506 0.067645 -1.027751 1.241759 -0.802948 -0.042958 -0.481909 -0.348129\n5497 15.762746 0.068014 -1.027452 1.240109 -0.808613 -0.041625 -0.481700 -0.335228\n5498 15.769630 0.068795 -1.027104 1.238529 -0.814124 -0.039677 -0.481337 -0.322402\n5499 15.777970 0.069242 -1.026968 1.236842 -0.819404 -0.036974 -0.480311 -0.310664\n5500 15.787996 0.069842 -1.026415 1.235195 -0.823527 -0.035060 -0.481646 -0.297643\n5501 15.795414 0.070769 -1.025905 1.233541 -0.827351 -0.033339 -0.483758 -0.283474\n5502 15.804753 0.071347 -1.024755 1.232157 -0.832694 -0.028778 -0.482728 -0.269752\n5503 15.812016 0.071820 -1.023934 1.230857 -0.836282 -0.025841 -0.484579 -0.255239\n5504 15.820809 0.072121 -1.023229 1.229657 -0.837613 -0.024315 -0.490062 -0.240111\n5505 15.829996 0.072701 -1.022516 1.228316 -0.840621 -0.021541 -0.492059 -0.225324\n5506 15.837167 0.072684 -1.022101 1.226625 -0.842748 -0.020268 -0.494735 -0.211194\n5507 15.844664 0.073337 -1.020979 1.225573 -0.843856 -0.017635 -0.499318 -0.195645\n5508 15.854721 0.073984 -1.020015 1.224834 -0.845855 -0.010698 -0.501732 -0.180775\n5509 15.862782 0.074310 -1.019382 1.223767 -0.847274 -0.008061 -0.504123 -0.167099\n5510 15.871823 0.074734 -1.018535 1.222829 -0.847976 -0.004315 -0.507167 -0.153948\n5511 15.879378 0.075013 -1.017685 1.221828 -0.848809 -0.000117 -0.509550 -0.141005\n5512 15.887616 0.075217 -1.017067 1.221016 -0.848456 0.003142 -0.513298 -0.128988\n5513 15.895508 0.075479 -1.016476 1.220176 -0.848292 0.004269 -0.516228 -0.117865\n5514 15.905964 0.075722 -1.015248 1.219416 -0.847598 0.006218 -0.519723 -0.106900\n5515 15.912849 0.075949 -1.014427 1.218809 -0.846440 0.007738 -0.523811 -0.095398\n5516 15.920632 0.076236 -1.013514 1.218332 -0.845593 0.007667 -0.527062 -0.084380\n5517 15.928237 0.076283 -1.012343 1.217876 -0.844068 0.007241 -0.531137 -0.073415\n5518 15.938468 0.076640 -1.011336 1.217605 -0.842420 0.005344 -0.535205 -0.062093\n5519 15.945086 0.076783 -1.010226 1.217438 -0.839563 0.003808 -0.540882 -0.050661\n5520 15.955097 0.076982 -1.008933 1.217095 -0.839803 0.002942 -0.541417 -0.039878\n5521 15.962200 0.077131 -1.007748 1.217102 -0.836998 0.000067 -0.546433 -0.029080\n5522 15.970242 0.077245 -1.006150 1.217194 -0.834697 -0.002795 -0.550359 -0.019465\n5523 15.980147 0.077424 -1.005211 1.217084 -0.832822 -0.004251 -0.553443 -0.009511\n5524 15.988563 0.077748 -1.004434 1.217553 -0.831023 -0.005986 -0.556206 -0.000455\n5525 15.996012 0.077741 -1.002902 1.217828 -0.827790 -0.007373 -0.560937 0.007737\n5526 16.004082 0.077789 -1.001962 1.218242 -0.824707 -0.009025 -0.565275 0.015518\n5527 16.011851 0.077594 -1.000896 1.218463 -0.821772 -0.010794 -0.569270 0.022467\n5528 16.022046 0.077378 -0.999499 1.219201 -0.816854 -0.013239 -0.575944 0.029369\n5529 16.029723 0.077383 -0.998975 1.219739 -0.812247 -0.015021 -0.581961 0.036759\n5530 16.038957 0.077245 -0.997767 1.220317 -0.808486 -0.017522 -0.586616 0.043869\n5531 16.047422 0.077092 -0.996487 1.221057 -0.802936 -0.019932 -0.593578 0.050618\n5532 16.056240 0.077052 -0.995379 1.221754 -0.797351 -0.022434 -0.600395 0.057043\n5533 16.062328 0.076934 -0.994145 1.222825 -0.792654 -0.025541 -0.605594 0.065601\n5534 16.071688 0.076774 -0.992925 1.223813 -0.785703 -0.027565 -0.613747 0.072296\n5535 16.078009 0.076852 -0.991816 1.224918 -0.780653 -0.028758 -0.619129 0.080206\n5536 16.086397 0.076577 -0.990776 1.225824 -0.772947 -0.031355 -0.627666 0.087205\n5537 16.095533 0.076264 -0.989459 1.227158 -0.765905 -0.033696 -0.635019 0.094896\n5538 16.102793 0.075859 -0.988321 1.228049 -0.757083 -0.036018 -0.644403 0.101358\n5539 16.112635 0.075445 -0.986827 1.229740 -0.749680 -0.037968 -0.651699 0.108746\n5540 16.121184 0.075045 -0.985683 1.231080 -0.743146 -0.040223 -0.657806 0.115792\n5541 16.129136 0.074026 -0.984977 1.232445 -0.732525 -0.042971 -0.667981 0.123943\n5542 16.137729 0.073965 -0.983704 1.233949 -0.725642 -0.045346 -0.673968 0.130975\n5543 16.145167 0.072172 -0.982114 1.235166 -0.712599 -0.048465 -0.686183 0.137864\n5544 16.154760 0.072205 -0.981420 1.236906 -0.705855 -0.051121 -0.691005 0.147203\n5545 16.162297 0.072600 -0.980413 1.238521 -0.700453 -0.055065 -0.694470 0.155066\n5546 16.171245 0.070422 -0.978956 1.239749 0.688782 0.057340 0.704338 -0.161862\n5547 16.179613 0.070467 -0.978089 1.241481 0.682961 0.061788 0.707179 -0.172178\n5548 16.187106 0.069688 -0.976881 1.242408 0.674848 0.065309 0.712663 -0.180072\n5549 16.195042 0.068986 -0.975994 1.244304 0.667469 0.069315 0.717023 -0.188571\n5550 16.205222 0.068130 -0.974992 1.245744 0.659103 0.073595 0.722154 -0.196622\n5551 16.211918 0.066953 -0.973902 1.247627 0.650880 0.079263 0.726754 -0.204700\n5552 16.221204 0.066372 -0.972844 1.249498 0.642487 0.083772 0.731511 -0.212333\n5553 16.228516 0.065640 -0.971944 1.251062 0.633567 0.088733 0.736276 -0.220494\n5554 16.236392 0.064037 -0.970445 1.253192 0.621487 0.093154 0.743339 -0.229178\n5555 16.246639 0.063210 -0.969552 1.255102 0.611545 0.099234 0.748298 -0.237098\n5556 16.254061 0.062066 -0.968371 1.256761 0.599887 0.103998 0.754434 -0.245252\n5557 16.261590 0.061028 -0.967254 1.258624 0.586461 0.108669 0.761360 -0.254135\n5558 16.269744 0.059545 -0.965883 1.260755 0.575148 0.114117 0.766095 -0.263211\n5559 16.278900 0.058187 -0.964857 1.262387 0.563103 0.118176 0.771205 -0.272384\n5560 16.286576 0.056888 -0.963413 1.264391 0.549725 0.123374 0.777039 -0.280698\n5561 16.294695 0.055899 -0.962193 1.266198 0.536619 0.128062 0.782535 -0.288582\n5562 16.302762 0.054194 -0.960849 1.269332 0.522656 0.133340 0.787631 -0.297807\n5563 16.312626 0.053077 -0.959843 1.270333 0.511929 0.136972 0.791660 -0.304043\n5564 16.321281 0.052177 -0.958318 1.272848 0.499836 0.140003 0.796930 -0.308976\n5565 16.329923 0.050341 -0.957816 1.274928 0.487644 0.144177 0.800805 -0.316430\n5566 16.336897 0.048642 -0.956476 1.276685 0.474409 0.147693 0.806670 -0.320011\n5567 16.344888 0.046726 -0.956074 1.278515 0.461095 0.150960 0.812550 -0.323057\n5568 16.357165 0.045053 -0.954772 1.280725 0.445386 0.156458 0.820061 -0.323500\n5569 16.362184 0.043875 -0.954362 1.281888 0.436500 0.161202 0.823981 -0.323322\n5570 16.369989 0.042882 -0.953418 1.283754 0.421311 0.163144 0.830891 -0.324809\n5571 16.379732 0.041924 -0.952587 1.285313 0.408626 0.166901 0.836980 -0.323472\n5572 16.387703 0.041047 -0.951611 1.287130 0.395292 0.177440 0.840360 -0.325659\n5573 16.394694 0.039900 -0.950769 1.288499 0.381607 0.183242 0.846968 -0.321625\n5574 16.405627 0.038462 -0.949610 1.290545 0.365558 0.192445 0.853462 -0.317702\n5575 16.412826 0.037911 -0.949107 1.291216 0.355435 0.197040 0.859121 -0.311052\n5576 16.421273 0.036056 -0.948570 1.293397 0.345552 0.201578 0.865536 -0.301343\n5577 16.429772 0.034747 -0.947852 1.295074 0.332911 0.206388 0.872667 -0.291592\n5578 16.437823 0.033315 -0.947370 1.296325 0.320696 0.212141 0.878879 -0.282350\n5579 16.446539 0.032162 -0.946646 1.297336 0.308802 0.214549 0.886106 -0.270973\n5580 16.453445 0.030074 -0.946838 1.298783 0.297110 0.217462 0.892513 -0.260492\n5581 16.461406 0.028815 -0.945484 1.300281 0.283571 0.220276 0.899533 -0.248810\n5582 16.469851 0.027464 -0.945185 1.302033 0.274003 0.219972 0.905773 -0.236876\n5583 16.479299 0.025685 -0.944772 1.303505 0.260264 0.219705 0.912861 -0.225115\n5584 16.487935 0.024115 -0.944282 1.304747 0.248077 0.220441 0.919034 -0.212696\n5585 16.496047 0.022479 -0.943898 1.306344 0.232681 0.221090 0.925543 -0.200871\n5586 16.505556 0.020348 -0.943741 1.307028 0.219351 0.219996 0.931606 -0.188671\n5587 16.512676 0.018640 -0.943261 1.308310 0.205500 0.219334 0.937479 -0.175486\n5588 16.522021 0.017186 -0.942892 1.309353 0.194350 0.219464 0.941994 -0.163432\n5589 16.529060 0.015347 -0.941710 1.309941 0.178969 0.218508 0.947167 -0.151987\n5590 16.538091 0.013175 -0.942003 1.311179 0.165492 0.217782 0.951511 -0.140748\n5591 16.545610 0.010720 -0.941619 1.312112 0.150652 0.217474 0.955700 -0.129021\n5592 16.554648 0.008877 -0.941339 1.313232 0.140525 0.215130 0.959364 -0.116587\n5593 16.562770 0.007202 -0.941223 1.313883 0.127781 0.212672 0.963080 -0.104500\n5594 16.569764 0.004706 -0.941116 1.314413 0.110564 0.209646 0.967010 -0.093365\n5595 16.577995 0.003107 -0.941099 1.314814 0.100677 0.204638 0.970177 -0.082122\n5596 16.588436 0.000677 -0.941270 1.315508 0.087070 0.199929 0.973357 -0.070872\n5597 16.596114 -0.001041 -0.941628 1.315927 0.073919 0.193861 0.976433 -0.059435\n5598 16.604512 -0.003673 -0.941862 1.316694 0.057040 0.189307 0.979067 -0.048344\n5599 16.612334 -0.005827 -0.942223 1.316789 0.044420 0.184416 0.981117 -0.037786\n5600 16.619696 -0.008350 -0.942787 1.316941 0.029017 0.180177 0.982840 -0.026821\n5601 16.629171 -0.010738 -0.943429 1.317118 0.017046 0.176555 0.984014 -0.015953\n5602 16.637905 -0.013007 -0.944226 1.317122 0.007017 0.171965 0.985066 -0.004975\n5603 16.644865 -0.015649 -0.945163 1.316836 -0.007031 0.167551 0.985820 0.005993\n5604 16.654828 -0.017585 -0.946330 1.316620 -0.013716 0.162332 0.986464 0.018667\n5605 16.662384 -0.020150 -0.946801 1.316501 -0.025717 0.158163 0.986587 0.031146\n5606 16.670062 -0.023035 -0.947703 1.316283 -0.043764 0.152964 0.986276 0.044116\n5607 16.680054 -0.025352 -0.948651 1.316174 -0.053531 0.145689 0.986217 0.057310\n5608 16.687347 -0.027910 -0.949325 1.315824 -0.065146 0.138296 0.985731 0.070461\n5609 16.695919 -0.030025 -0.950403 1.315436 -0.071176 0.130297 0.985412 0.083192\n5610 16.702751 -0.033024 -0.951064 1.315101 -0.086961 0.121324 0.984203 0.095198\n5611 16.712044 -0.035447 -0.952217 1.314707 -0.097091 0.112415 0.983100 0.107005\n5612 16.721425 -0.038358 -0.953266 1.314132 -0.109009 0.103376 0.981597 0.117887\n5613 16.729197 -0.040496 -0.955379 1.313594 -0.115743 0.094200 0.980432 0.128386\n5614 16.736356 -0.042953 -0.955922 1.312872 -0.126616 0.083718 0.978621 0.138784\n5615 16.744644 -0.046178 -0.957367 1.312167 -0.135698 0.075066 0.976954 0.146671\n5616 16.755618 -0.048653 -0.959369 1.310853 -0.143939 0.066385 0.975321 0.153699\n5617 16.762004 -0.052304 -0.961221 1.310262 -0.164335 0.056126 0.971854 0.159196\n5618 16.771284 -0.055151 -0.962866 1.309095 -0.177345 0.047792 0.969002 0.165225\n5619 16.779363 -0.057910 -0.964909 1.308040 -0.187453 0.039386 0.966598 0.170291\n5620 16.786198 -0.060675 -0.967339 1.306809 -0.192629 0.034794 0.964960 0.174744\n5621 16.795786 -0.063910 -0.969157 1.305055 -0.208051 0.024239 0.961553 0.177603\n5622 16.804139 -0.066716 -0.971308 1.304012 -0.221235 0.014526 0.958560 0.178904\n5623 16.811306 -0.069587 -0.973721 1.302463 -0.233913 0.004585 0.955288 0.180799\n5624 16.822610 -0.072633 -0.975853 1.300941 -0.250049 -0.006615 0.951068 0.181385\n5625 16.828925 -0.075512 -0.978079 1.299151 -0.260308 -0.016468 0.947964 0.182575\n5626 16.837429 -0.078850 -0.980452 1.297207 -0.272676 -0.026404 0.944164 0.183045\n5627 16.846073 -0.082069 -0.982605 1.295453 -0.287745 -0.038040 0.939673 0.181027\n5628 16.854295 -0.084373 -0.984944 1.293844 -0.297103 -0.047354 0.936513 0.180089\n5629 16.861343 -0.087674 -0.987123 1.291778 -0.306853 -0.057402 0.932447 0.181905\n5630 16.871781 -0.090723 -0.989237 1.289847 -0.318186 -0.067432 0.928149 0.180968\n5631 16.878999 -0.093699 -0.991207 1.287828 -0.328161 -0.076408 0.924097 0.180325\n5632 16.887943 -0.096591 -0.993044 1.285710 -0.333878 -0.083934 0.920646 0.184097\n5633 16.895577 -0.099227 -0.994766 1.284213 -0.342738 -0.094376 0.916575 0.183069\n5634 16.903026 -0.101640 -0.997011 1.282362 -0.347452 -0.102155 0.913499 0.185368\n5635 16.911286 -0.103910 -0.999103 1.280376 -0.352318 -0.108470 0.910806 0.185845\n5636 16.922653 -0.106632 -1.000765 1.278555 -0.357213 -0.116726 0.907236 0.188938\n5637 16.929360 -0.109302 -1.002270 1.276681 -0.361777 -0.123939 0.904115 0.190613\n5638 16.937775 -0.111607 -1.004177 1.274818 -0.365362 -0.130281 0.901137 0.193622\n5639 16.945486 -0.114023 -1.005605 1.273006 -0.369411 -0.136383 0.897909 0.196711\n5640 16.952956 -0.116355 -1.007256 1.271276 -0.372924 -0.142974 0.894543 0.200699\n5641 16.963383 -0.118829 -1.008783 1.269161 -0.377429 -0.147944 0.890974 0.204512\n5642 16.970807 -0.121334 -1.010279 1.267262 -0.382935 -0.153684 0.886815 0.208090\n5643 16.978910 -0.123765 -1.011946 1.265156 -0.388496 -0.158858 0.882750 0.211159\n5644 16.986231 -0.126159 -1.013503 1.263030 -0.393905 -0.163920 0.878390 0.215406\n5645 16.995535 -0.128818 -1.014896 1.260821 -0.399939 -0.169190 0.873516 0.219987\n5646 17.004776 -0.131183 -1.016180 1.258439 -0.406951 -0.174200 0.868055 0.224781\n5647 17.013193 -0.133426 -1.018192 1.256267 -0.411504 -0.179354 0.863962 0.228180\n5648 17.020281 -0.136055 -1.019625 1.253833 -0.417657 -0.184219 0.859048 0.231652\n5649 17.028034 -0.138563 -1.020930 1.251292 -0.423740 -0.189453 0.854131 0.234550\n5650 17.038281 -0.140974 -1.022320 1.248641 -0.431198 -0.194139 0.848629 0.237080\n5651 17.045430 -0.143283 -1.023711 1.246321 -0.436483 -0.199271 0.844103 0.239301\n5652 17.054538 -0.145730 -1.025376 1.243589 -0.442989 -0.205259 0.838699 0.241274\n5653 17.062964 -0.148148 -1.026625 1.241262 -0.450057 -0.208519 0.833432 0.243639\n5654 17.069635 -0.150606 -1.027805 1.239403 -0.457092 -0.210990 0.828238 0.246115\n5655 17.080059 -0.152637 -1.029244 1.237128 -0.461929 -0.215681 0.823804 0.247893\n5656 17.087435 -0.155067 -1.029989 1.235552 -0.465206 -0.217121 0.820583 0.251168\n5657 17.094820 -0.156865 -1.030779 1.233509 -0.468216 -0.217439 0.817707 0.254657\n5658 17.103951 -0.158956 -1.031756 1.231599 -0.468628 -0.222862 0.815216 0.257182\n5659 17.112407 -0.161280 -1.032952 1.229805 -0.470992 -0.223977 0.812048 0.261873\n5660 17.119456 -0.163157 -1.032210 1.228555 -0.470988 -0.227690 0.809695 0.265937\n5661 17.129323 -0.165006 -1.032805 1.227234 -0.472351 -0.231149 0.806089 0.271434\n5662 17.137768 -0.166949 -1.032788 1.226306 -0.471490 -0.234210 0.803986 0.276494\n5663 17.144586 -0.168585 -1.032927 1.225866 -0.473292 -0.232522 0.801302 0.282568\n5664 17.154942 -0.169845 -1.032803 1.225539 -0.473425 -0.234648 0.798546 0.288327\n5665 17.162436 -0.171086 -1.031670 1.225613 -0.473420 -0.233967 0.796680 0.293998\n5666 17.171049 -0.172287 -1.031780 1.225687 -0.472244 -0.233430 0.795243 0.300140\n5667 17.179699 -0.173129 -1.031060 1.226168 -0.470984 -0.232846 0.794434 0.304683\n5668 17.186329 -0.174198 -1.030670 1.226650 -0.469755 -0.231688 0.794088 0.308342\n5669 17.194614 -0.175334 -1.030131 1.227306 -0.467627 -0.229963 0.793466 0.314412\n5670 17.204733 -0.176187 -1.028933 1.228151 -0.466812 -0.226527 0.793525 0.317947\n5671 17.211852 -0.176829 -1.028495 1.229200 -0.462165 -0.227067 0.794661 0.321494\n5672 17.221243 -0.177180 -1.027623 1.230652 -0.458487 -0.224309 0.796614 0.323855\n5673 17.228718 -0.177573 -1.026391 1.232311 -0.454162 -0.221662 0.798402 0.327348\n5674 17.236371 -0.177684 -1.024902 1.234275 -0.448070 -0.220505 0.800886 0.330442\n5675 17.244693 -0.177727 -1.023115 1.236356 -0.442421 -0.216044 0.803407 0.334853\n5676 17.252966 -0.177798 -1.021569 1.238910 -0.434075 -0.212378 0.807014 0.339416\n5677 17.262637 -0.177198 -1.019708 1.241976 -0.424532 -0.207364 0.811420 0.344049\n5678 17.271376 -0.176291 -1.018230 1.245513 -0.413778 -0.201562 0.816562 0.348406\n5679 17.279277 -0.175185 -1.016974 1.249229 -0.402520 -0.194033 0.821389 0.354470\n5680 17.288080 -0.173582 -1.015618 1.253682 -0.387046 -0.187391 0.828172 0.359460\n5681 17.297677 -0.171690 -1.014508 1.257714 -0.371701 -0.179453 0.834610 0.364774\n5682 17.303906 -0.169481 -1.013535 1.262026 -0.353243 -0.171270 0.842202 0.369571\n5683 17.311311 -0.167109 -1.012626 1.266396 -0.334092 -0.163730 0.849333 0.374444\n5684 17.320511 -0.164531 -1.011584 1.270340 -0.312372 -0.156354 0.856823 0.379251\n5685 17.329841 -0.161976 -1.010472 1.274223 -0.291137 -0.149268 0.863563 0.383689\n5686 17.337966 -0.159354 -1.009327 1.278008 -0.269915 -0.143259 0.869173 0.388795\n5687 17.346255 -0.156697 -1.008362 1.281682 -0.246702 -0.138096 0.874913 0.393187\n5688 17.353727 -0.153783 -1.006932 1.284834 -0.224718 -0.133172 0.878801 0.399344\n5689 17.361323 -0.151107 -1.006058 1.288590 -0.205492 -0.127496 0.881886 0.404716\n5690 17.370363 -0.147633 -1.004640 1.291879 -0.184985 -0.122909 0.884653 0.409954\n5691 17.379379 -0.145283 -1.004190 1.295481 -0.167779 -0.112991 0.886229 0.416752\n5692 17.386259 -0.141703 -1.002368 1.298874 -0.149338 -0.105154 0.887769 0.422502\n5693 17.395408 -0.138433 -1.001710 1.301445 -0.134012 -0.099837 0.887778 0.428862\n5694 17.404608 -0.134339 -1.000815 1.304430 -0.117564 -0.090509 0.886823 0.437644\n5695 17.411322 -0.130893 -0.999988 1.307805 -0.098761 -0.081109 0.887222 0.443290\n5696 17.420624 -0.126901 -0.999347 1.310658 -0.078574 -0.073867 0.886327 0.450327\n5697 17.428942 -0.123155 -0.998498 1.313254 -0.062423 -0.063448 0.885779 0.455493\n5698 17.436871 -0.119462 -0.997871 1.315606 -0.042764 -0.056339 0.883717 0.462647\n5699 17.447944 -0.115634 -0.997461 1.317807 -0.021528 -0.048907 0.882409 0.467438\n5700 17.453894 -0.111670 -0.996536 1.319767 -0.003879 -0.039160 0.880171 0.473022\n5701 17.461247 -0.107876 -0.996002 1.321714 0.017194 -0.033652 0.877144 0.478739\n5702 17.469350 -0.104068 -0.995373 1.323428 0.037449 -0.027616 0.874073 0.483560\n5703 17.479737 -0.100238 -0.995012 1.325056 0.057754 -0.022325 0.869976 0.489191\n5704 17.488244 -0.096600 -0.994884 1.326604 0.077701 -0.017437 0.864570 0.496162\n5705 17.496252 -0.092557 -0.994732 1.327877 0.097269 -0.014960 0.859356 0.501818\n5706 17.503999 -0.088726 -0.994278 1.329414 0.116701 -0.009621 0.853339 0.508036\n5707 17.513329 -0.084539 -0.994279 1.330470 0.134850 -0.004124 0.848434 0.511818\n5708 17.521332 -0.081420 -0.993667 1.331834 0.154212 -0.001375 0.840851 0.518832\n5709 17.528797 -0.077417 -0.993304 1.332803 0.173822 0.002983 0.835158 0.521813\n5710 17.536372 -0.073687 -0.993306 1.333687 0.192791 0.006858 0.828350 0.525948\n5711 17.545711 -0.069978 -0.992776 1.334491 0.209454 0.012093 0.821882 0.529615\n5712 17.554689 -0.066082 -0.992647 1.334907 0.228721 0.016557 0.813643 0.534226\n5713 17.563040 -0.062636 -0.992959 1.335367 0.247573 0.018725 0.805822 0.537594\n5714 17.571698 -0.058949 -0.993141 1.335249 0.267244 0.017392 0.796279 0.542418\n5715 17.579568 -0.055438 -0.994195 1.335754 0.284069 0.020544 0.788019 0.545811\n5716 17.587661 -0.051946 -0.994746 1.335890 0.301989 0.021990 0.778494 0.549788\n5717 17.594574 -0.048367 -0.994955 1.336026 0.315640 0.025261 0.769408 0.554748\n5718 17.605264 -0.044997 -0.995517 1.335460 0.337117 0.024311 0.758636 0.556985\n5719 17.612404 -0.041718 -0.995838 1.335081 0.354824 0.025409 0.747777 0.560610\n5720 17.621092 -0.038361 -0.996569 1.334811 0.370596 0.025450 0.737287 0.564286\n5721 17.628680 -0.035038 -0.997099 1.334364 0.388637 0.025361 0.725984 0.566803\n5722 17.636737 -0.032085 -0.997243 1.333472 0.403556 0.029398 0.716328 0.568466\n5723 17.646667 -0.029571 -0.998083 1.333193 0.419131 0.028999 0.705444 0.570822\n5724 17.655001 -0.026726 -0.998413 1.332243 0.435232 0.029803 0.694475 0.572180\n5725 17.663170 -0.024298 -0.998842 1.331645 0.450816 0.030848 0.682197 0.574822\n5726 17.670202 -0.022056 -0.999836 1.330912 0.464958 0.031088 0.670276 0.577562\n5727 17.678180 -0.019735 -0.999984 1.329983 0.478988 0.031936 0.658450 0.579650\n5728 17.687271 -0.017746 -1.001163 1.329045 0.490964 0.031125 0.647546 0.581953\n5729 17.695167 -0.016270 -1.001955 1.328083 0.506431 0.030264 0.632962 0.584782\n5730 17.704622 -0.013876 -1.002321 1.326515 0.517739 0.032146 0.620284 0.588354\n5731 17.713181 -0.012822 -1.003619 1.326588 0.531966 0.029190 0.607177 0.589489\n5732 17.720211 -0.011185 -1.004076 1.325300 0.541149 0.029323 0.595967 0.592555\n5733 17.730253 -0.009506 -1.004612 1.323662 0.551575 0.029079 0.584301 0.594568\n5734 17.737095 -0.007836 -1.004698 1.323112 0.563295 0.029290 0.572913 0.594653\n5735 17.744710 -0.006664 -1.005737 1.322375 0.574613 0.027177 0.560674 0.595590\n5736 17.752924 -0.005944 -1.006609 1.321926 0.586436 0.027289 0.546371 0.597350\n5737 17.762033 -0.004632 -1.006981 1.320266 0.593711 0.026311 0.537313 0.598423\n5738 17.769667 -0.003987 -1.007723 1.319749 0.603764 0.024692 0.525315 0.599085\n5739 17.779782 -0.003186 -1.008772 1.318155 0.612124 0.024337 0.512826 0.601433\n5740 17.786960 -0.002378 -1.009631 1.317338 0.619723 0.022566 0.501969 0.602878\n5741 17.794674 -0.002055 -1.010635 1.316466 0.631012 0.019946 0.489138 0.601806\n5742 17.803104 -0.000422 -1.010859 1.314864 0.635444 0.022620 0.481638 0.603096\n5743 17.812129 -0.000276 -1.012095 1.314305 0.645297 0.018226 0.467302 0.604060\n5744 17.819559 0.000723 -1.012502 1.312141 0.653863 0.016796 0.457290 0.602551\n5745 17.829130 0.001678 -1.012503 1.312667 0.661047 0.018930 0.446363 0.602842\n5746 17.838040 0.003133 -1.012896 1.311218 0.668831 0.019733 0.436074 0.601761\n5747 17.844575 0.003860 -1.012902 1.310756 0.674760 0.022861 0.428455 0.600502\n5748 17.853152 0.004749 -1.013316 1.309424 0.680652 0.023990 0.420718 0.599277\n5749 17.862456 0.005518 -1.013329 1.308661 0.687242 0.026212 0.411179 0.598284\n5750 17.871076 0.006394 -1.013604 1.307619 0.694038 0.030479 0.402416 0.596191\n5751 17.879671 0.007391 -1.013305 1.306652 0.697972 0.031922 0.396082 0.595765\n5752 17.886234 0.007272 -1.014052 1.306008 0.703532 0.033382 0.385631 0.596001\n5753 17.894502 0.008291 -1.013991 1.305386 0.707372 0.035965 0.378467 0.595897\n5754 17.904968 0.008491 -1.014336 1.304772 0.711435 0.038561 0.371872 0.595050\n5755 17.912686 0.009319 -1.014501 1.304469 0.715128 0.039039 0.364192 0.595342\n5756 17.921087 0.009825 -1.014323 1.302907 0.717523 0.042150 0.359045 0.595374\n5757 17.929410 0.011124 -1.014543 1.302423 0.720867 0.043935 0.353104 0.594759\n5758 17.936497 0.012166 -1.013976 1.302421 0.721229 0.047113 0.351584 0.594977\n5759 17.945911 0.012589 -1.014277 1.301706 0.723329 0.048473 0.345543 0.595857\n5760 17.954629 0.014132 -1.014040 1.301352 0.723737 0.049335 0.343124 0.596688\n5761 17.963390 0.014425 -1.013949 1.300387 0.725584 0.048823 0.338913 0.596894\n5762 17.971589 0.015076 -1.014904 1.301079 0.727972 0.050757 0.332809 0.597259\n5763 17.979162 0.016758 -1.013329 1.300662 0.720399 0.055077 0.339410 0.602322\n5764 17.987229 0.017810 -1.013431 1.301388 0.718361 0.058007 0.340193 0.604038\n5765 17.994708 0.018670 -1.012827 1.301166 0.712094 0.060872 0.341658 0.610316\n5766 18.004353 0.019750 -1.011437 1.302057 0.705771 0.067553 0.352025 0.611067\n5767 18.012786 0.020936 -1.011349 1.301012 0.701262 0.071501 0.351929 0.615845\n5768 18.019629 0.021875 -1.010460 1.302466 0.692032 0.080474 0.356735 0.622379\n5769 18.027946 0.022335 -1.010165 1.302731 0.685174 0.086680 0.360348 0.627035\n5770 18.037741 0.023397 -1.008848 1.303154 0.676735 0.096814 0.366937 0.630884\n5771 18.046670 0.024531 -1.008143 1.303794 0.667544 0.103440 0.374400 0.635224\n5772 18.054261 0.025441 -1.006963 1.303914 0.658657 0.111374 0.380073 0.639775\n5773 18.061886 0.026162 -1.006477 1.305835 0.651117 0.115548 0.382648 0.645195\n5774 18.069567 0.026860 -1.005460 1.306389 0.641347 0.122400 0.388162 0.650402\n5775 18.079987 0.027629 -1.004303 1.307537 0.631273 0.129160 0.393635 0.655640\n5776 18.087025 0.028139 -1.003011 1.308340 0.620261 0.137786 0.400222 0.660389\n5777 18.095617 0.028417 -1.001847 1.308877 0.608604 0.145768 0.408137 0.664663\n5778 18.104295 0.028956 -1.000572 1.310008 0.596833 0.153851 0.415114 0.669179\n5779 18.112302 0.029413 -0.998930 1.310634 0.586978 0.162072 0.420574 0.672538\n5780 18.120417 0.029996 -0.997544 1.311650 0.575443 0.169711 0.428247 0.675772\n5781 18.128380 0.030348 -0.996070 1.312273 0.564368 0.178480 0.435094 0.678474\n5782 18.137607 0.030969 -0.994603 1.313398 0.552512 0.186833 0.442284 0.681329\n5783 18.146336 0.031257 -0.992944 1.313808 0.541333 0.194984 0.451260 0.682132\n5784 18.153356 0.031688 -0.991406 1.314835 0.529237 0.202725 0.459014 0.684190\n5785 18.161233 0.031791 -0.989620 1.315560 0.517054 0.210781 0.467167 0.685552\n5786 18.171529 0.032190 -0.987930 1.315933 0.506526 0.219441 0.475025 0.685294\n5787 18.179578 0.031797 -0.985868 1.316729 0.492926 0.225664 0.484274 0.686715\n5788 18.187579 0.031498 -0.983929 1.317613 0.480202 0.233101 0.492696 0.687256\n5789 18.195936 0.031100 -0.981734 1.318337 0.466857 0.243884 0.502362 0.685710\n5790 18.203048 0.030067 -0.980212 1.319265 0.456160 0.247883 0.510731 0.685292\n5791 18.212671 0.030370 -0.977803 1.320073 0.441891 0.257134 0.517612 0.686070\n5792 18.221936 0.030113 -0.975360 1.320776 0.430855 0.262623 0.527109 0.683775\n5793 18.229270 0.029817 -0.973836 1.321618 0.417947 0.266140 0.532051 0.686594\n5794 18.237826 0.028834 -0.971157 1.322164 0.406026 0.271425 0.540914 0.684751\n5795 18.245598 0.028216 -0.969016 1.322814 0.391895 0.276307 0.550048 0.683755\n5796 18.253167 0.027352 -0.966873 1.323193 0.378222 0.279478 0.559005 0.682901\n5797 18.262804 0.026560 -0.964819 1.323743 0.363481 0.283064 0.568399 0.681674\n5798 18.271824 0.025770 -0.962723 1.324246 0.348303 0.285849 0.578003 0.680358\n5799 18.279202 0.024932 -0.960819 1.324571 0.332939 0.287951 0.588207 0.678416\n5800 18.286721 0.024022 -0.958891 1.324973 0.316688 0.290075 0.598517 0.676271\n5801 18.294527 0.023203 -0.956912 1.325267 0.300421 0.292024 0.608605 0.673846\n5802 18.304292 0.022222 -0.955115 1.325506 0.284126 0.293748 0.619011 0.670678\n5803 18.312126 0.021157 -0.953287 1.325783 0.267438 0.295922 0.629416 0.666890\n5804 18.320535 0.020042 -0.951637 1.325942 0.251867 0.298167 0.639052 0.662776\n5805 18.328721 0.018814 -0.949821 1.326103 0.235577 0.299799 0.649856 0.657504\n5806 18.337695 0.017519 -0.948128 1.326274 0.219572 0.302684 0.659932 0.651660\n5807 18.344719 0.016041 -0.946443 1.326002 0.203419 0.305693 0.670400 0.644777\n5808 18.355618 0.014594 -0.944759 1.326116 0.187743 0.308221 0.680268 0.637956\n5809 18.361798 0.013025 -0.943213 1.326191 0.172211 0.310233 0.690296 0.630548\n5810 18.370879 0.011441 -0.941560 1.326167 0.156797 0.311577 0.699883 0.623297\n5811 18.379427 0.009849 -0.940122 1.326258 0.142879 0.311586 0.709180 0.616087\n5812 18.386325 0.008021 -0.938813 1.326169 0.127680 0.311180 0.718844 0.608381\n5813 18.396507 0.006080 -0.937645 1.326068 0.112742 0.309759 0.728224 0.600856\n5814 18.404926 0.004329 -0.936748 1.326260 0.098947 0.306080 0.737855 0.593376\n5815 18.411906 0.001963 -0.935412 1.326004 0.081203 0.305463 0.747797 0.583865\n5816 18.420666 -0.000317 -0.935109 1.325919 0.066367 0.301422 0.756429 0.576677\n5817 18.428643 -0.002577 -0.934182 1.325830 0.052508 0.297204 0.765232 0.568623\n5818 18.436411 -0.005120 -0.933646 1.325801 0.038730 0.291496 0.773512 0.561435\n5819 18.446289 -0.007074 -0.933383 1.325688 0.025099 0.286914 0.781559 0.553367\n5820 18.453898 -0.009398 -0.933703 1.325541 0.011032 0.280169 0.788888 0.546846\n5821 18.462852 -0.011621 -0.933689 1.325209 -0.002254 0.274665 0.796128 0.539197\n5822 18.469773 -0.013558 -0.933288 1.324452 -0.019319 0.268973 0.803737 0.530366\n5823 18.479187 -0.016328 -0.933636 1.324527 -0.031858 0.262680 0.810646 0.522338\n5824 18.486471 -0.018661 -0.934052 1.324263 -0.044169 0.256667 0.816981 0.514503\n5825 18.494488 -0.020704 -0.934438 1.323757 -0.057249 0.250471 0.823698 0.505479\n5826 18.503401 -0.022256 -0.934551 1.322989 -0.070187 0.244670 0.830983 0.494648\n5827 18.516510 -0.024588 -0.935460 1.322211 -0.085585 0.239291 0.837300 0.484090\n5828 18.522176 -0.026839 -0.935948 1.321933 -0.096425 0.233696 0.843188 0.474470\n5829 18.527933 -0.028840 -0.936775 1.321207 -0.107405 0.227572 0.849683 0.463372\n5830 18.536942 -0.030569 -0.937561 1.320781 -0.122168 0.221185 0.855569 0.451834\n5831 18.546971 -0.032238 -0.938695 1.320355 -0.131582 0.215472 0.861908 0.439741\n5832 18.555696 -0.034153 -0.938627 1.319146 -0.146546 0.209524 0.867188 0.427328\n5833 18.565221 -0.035313 -0.940042 1.318552 -0.153486 0.202757 0.873445 0.415242\n5834 18.573824 -0.037256 -0.940811 1.317694 -0.162823 0.198795 0.879034 0.401583\n5835 18.578975 -0.039054 -0.941567 1.317100 -0.175256 0.194250 0.883705 0.388096\n5836 18.590635 -0.040533 -0.942509 1.316489 -0.184598 0.190268 0.888658 0.374176\n5837 18.596916 -0.042122 -0.943372 1.315718 -0.194214 0.187092 0.892773 0.360881\n5838 18.604714 -0.043690 -0.944738 1.314841 -0.204419 0.184193 0.896850 0.346333\n5839 18.613554 -0.044977 -0.945683 1.314242 -0.212619 0.181100 0.900788 0.332531\n5840 18.620702 -0.046142 -0.946777 1.313610 -0.218536 0.179733 0.904485 0.319132\n5841 18.628327 -0.047208 -0.947719 1.312448 -0.227500 0.176337 0.907624 0.305562\n5842 18.637441 -0.047880 -0.948889 1.311906 -0.235233 0.176925 0.910440 0.290623\n5843 18.645196 -0.048820 -0.949388 1.311231 -0.241433 0.176835 0.913262 0.276391\n5844 18.654866 -0.049949 -0.950323 1.310136 -0.245390 0.175662 0.917091 0.260522\n5845 18.663825 -0.050506 -0.951414 1.309216 -0.252060 0.176565 0.919274 0.245411\n5846 18.671267 -0.051131 -0.951874 1.308547 -0.257132 0.177547 0.921740 0.229685\n5847 18.680064 -0.051863 -0.952567 1.308368 -0.260347 0.179033 0.924451 0.213440\n5848 18.687636 -0.052355 -0.953583 1.307881 -0.264741 0.180084 0.926641 0.197022\n5849 18.695973 -0.052741 -0.954227 1.307336 -0.267658 0.181861 0.928655 0.181341\n5850 18.704251 -0.053306 -0.954892 1.306776 -0.271750 0.183137 0.930309 0.164735\n5851 18.712578 -0.053293 -0.955688 1.306433 -0.273430 0.185830 0.931809 0.149782\n5852 18.720887 -0.053552 -0.956211 1.306033 -0.275680 0.187446 0.933184 0.134284\n5853 18.728577 -0.053595 -0.957253 1.306106 -0.276682 0.190506 0.934377 0.118719\n5854 18.737352 -0.053565 -0.957754 1.305711 -0.277317 0.193909 0.935152 0.104808\n5855 18.746074 -0.053268 -0.958857 1.305684 -0.277374 0.196004 0.936394 0.088385\n5856 18.753784 -0.052979 -0.959172 1.305533 -0.277962 0.201632 0.936346 0.073058\n5857 18.761508 -0.052886 -0.960102 1.305544 -0.279637 0.204145 0.936257 0.059598\n5858 18.771170 -0.052795 -0.960614 1.305452 -0.280620 0.208297 0.935849 0.045300\n5859 18.779115 -0.052513 -0.961321 1.305323 -0.282480 0.211950 0.935037 0.031436\n5860 18.787459 -0.052052 -0.962008 1.305162 -0.282354 0.216860 0.934290 0.018690\n5861 18.795796 -0.051833 -0.961939 1.304893 -0.283566 0.218386 0.933725 0.007516\n5862 18.802911 -0.051151 -0.962781 1.304807 -0.285493 0.218050 0.933232 -0.005186\n5863 18.813174 -0.051392 -0.963058 1.304978 -0.288690 0.220423 0.931574 -0.015558\n5864 18.820352 -0.050925 -0.963401 1.304883 -0.289441 0.219613 0.931288 -0.026412\n5865 18.828873 -0.050938 -0.963727 1.304783 -0.292674 0.218836 0.930104 -0.036861\n5866 18.836248 -0.050633 -0.964656 1.304661 -0.292259 0.217815 0.930007 -0.047195\n5867 18.846374 -0.050168 -0.964297 1.304160 -0.293311 0.214306 0.930084 -0.054630\n5868 18.852780 -0.050105 -0.964938 1.303774 -0.292727 0.209638 0.930537 -0.066817\n5869 18.862504 -0.050768 -0.965771 1.303987 -0.296121 0.207727 0.929528 -0.071688\n5870 18.871105 -0.050778 -0.966809 1.303857 -0.296361 0.203707 0.929684 -0.079759\n5871 18.877817 -0.050056 -0.967616 1.304022 -0.295989 0.196584 0.930802 -0.085755\n5872 18.886641 -0.049933 -0.968071 1.304191 -0.297342 0.190747 0.930906 -0.092834\n5873 18.895735 -0.049380 -0.968885 1.304358 -0.294246 0.183602 0.932448 -0.101246\n5874 18.902901 -0.049036 -0.969961 1.304551 -0.293488 0.177664 0.933057 -0.108193\n5875 18.911500 -0.048568 -0.970156 1.304638 -0.292508 0.170461 0.933872 -0.115172\n5876 18.921451 -0.048182 -0.971070 1.305063 -0.293830 0.163706 0.934081 -0.119819\n5877 18.928823 -0.047563 -0.970963 1.305266 -0.289070 0.155430 0.936314 -0.124885\n5878 18.937472 -0.046551 -0.973731 1.305390 -0.282893 0.147620 0.938786 -0.129850\n5879 18.946052 -0.047158 -0.973638 1.305656 -0.284625 0.141802 0.938441 -0.134944\n5880 18.953419 -0.046669 -0.973867 1.305864 -0.277919 0.131309 0.941532 -0.137973\n5881 18.963796 -0.046107 -0.974968 1.306229 -0.273526 0.122871 0.943434 -0.141487\n5882 18.970759 -0.045942 -0.975517 1.306246 -0.269444 0.113688 0.945595 -0.142565\n5883 18.982578 -0.044579 -0.975842 1.307031 -0.261621 0.104082 0.948532 -0.144942\n5884 18.988006 -0.044642 -0.976387 1.306592 -0.252583 0.094178 0.952115 -0.144256\n5885 18.996054 -0.044345 -0.977144 1.306630 -0.245395 0.083655 0.954897 -0.144761\n5886 19.003448 -0.044054 -0.977995 1.306666 -0.239572 0.075499 0.957042 -0.144832\n5887 19.013143 -0.043532 -0.978958 1.306711 -0.232388 0.062778 0.959803 -0.144338\n5888 19.021169 -0.042859 -0.979605 1.306776 -0.224976 0.053781 0.962098 -0.144432\n5889 19.029521 -0.042758 -0.980712 1.306750 -0.218141 0.040198 0.964235 -0.145084\n5890 19.036384 -0.042348 -0.981969 1.307123 -0.213274 0.027923 0.965710 -0.145394\n5891 19.045893 -0.042255 -0.982728 1.307430 -0.205489 0.017951 0.967675 -0.145114\n5892 19.052993 -0.041755 -0.983754 1.307703 -0.199625 0.007348 0.969151 -0.144365\n5893 19.061416 -0.041579 -0.986377 1.307552 -0.194180 -0.002211 0.970254 -0.144557\n5894 19.070720 -0.040534 -0.986872 1.307717 -0.184538 -0.013779 0.972473 -0.141602\n5895 19.078537 -0.040945 -0.987428 1.307582 -0.180603 -0.022237 0.973479 -0.138662\n5896 19.087650 -0.040430 -0.990206 1.307306 -0.174617 -0.030337 0.974347 -0.138697\n5897 19.095238 -0.040212 -0.990639 1.307458 -0.169018 -0.039922 0.975697 -0.133620\n5898 19.102986 -0.040291 -0.992501 1.306642 -0.164280 -0.047860 0.976530 -0.130811\n5899 19.112770 -0.040035 -0.993245 1.307126 -0.163014 -0.055388 0.976790 -0.127436\n5900 19.120744 -0.039947 -0.994152 1.306967 -0.160733 -0.063187 0.977349 -0.122313\n5901 19.129966 -0.039731 -0.995464 1.306816 -0.158814 -0.071104 0.977677 -0.117773\n5902 19.137955 -0.039960 -0.997498 1.306320 -0.159553 -0.077422 0.977566 -0.113634\n5903 19.146109 -0.039897 -0.997434 1.306342 -0.159217 -0.084352 0.977782 -0.107134\n5904 19.155174 -0.040258 -0.999091 1.305995 -0.161962 -0.089484 0.977282 -0.103347\n5905 19.163130 -0.040212 -1.000626 1.305824 -0.158635 -0.095949 0.977622 -0.099417\n5906 19.170839 -0.040394 -1.001304 1.305689 -0.158696 -0.100649 0.977713 -0.093610\n5907 19.179193 -0.040463 -1.002543 1.305510 -0.157406 -0.105013 0.977934 -0.088549\n5908 19.187713 -0.040384 -1.002875 1.305317 -0.153804 -0.110942 0.978174 -0.084928\n5909 19.196433 -0.040715 -1.004684 1.305214 -0.154851 -0.113912 0.978169 -0.078933\n5910 19.203739 -0.040433 -1.005871 1.305135 -0.150909 -0.119206 0.978541 -0.073987\n5911 19.211098 -0.040245 -1.006987 1.305003 -0.147382 -0.124721 0.978719 -0.069516\n5912 19.221105 -0.039733 -1.008229 1.304916 -0.142095 -0.131097 0.978980 -0.064965\n5913 19.228994 -0.039270 -1.009410 1.304804 -0.135377 -0.137594 0.979325 -0.060524\n5914 19.237879 -0.038553 -1.010540 1.304825 -0.126481 -0.144483 0.979777 -0.056256\n5915 19.245633 -0.038008 -1.011726 1.304905 -0.119067 -0.151683 0.979844 -0.052164\n5916 19.253130 -0.037257 -1.012971 1.304953 -0.108544 -0.158381 0.980212 -0.048139\n5917 19.263102 -0.036514 -1.013712 1.305155 -0.100184 -0.164182 0.980360 -0.043619\n5918 19.270797 -0.036234 -1.014738 1.305113 -0.093321 -0.168940 0.980385 -0.039937\n5919 19.279164 -0.035643 -1.015844 1.305146 -0.085272 -0.173435 0.980484 -0.036055\n5920 19.286761 -0.035081 -1.016788 1.305173 -0.077213 -0.178646 0.980383 -0.031184\n5921 19.296149 -0.033625 -1.017766 1.304921 -0.065446 -0.185833 0.980069 -0.025433\n5922 19.302895 -0.032875 -1.019158 1.304668 -0.060928 -0.189740 0.979725 -0.020608\n5923 19.312357 -0.031795 -1.019986 1.304570 -0.051385 -0.195233 0.979325 -0.012864\n5924 19.320788 -0.031352 -1.021316 1.304529 -0.047432 -0.199346 0.978756 -0.006882\n5925 19.328352 -0.030361 -1.022324 1.304327 -0.038911 -0.204146 0.978167 0.000363\n5926 19.337774 -0.028948 -1.023264 1.304158 -0.028838 -0.209427 0.977375 0.006905\n5927 19.345418 -0.028495 -1.024454 1.303916 -0.021296 -0.213332 0.976635 0.014831\n5928 19.353443 -0.027723 -1.025589 1.303694 -0.014694 -0.217430 0.975710 0.022321\n5929 19.361376 -0.026165 -1.026219 1.303559 -0.004220 -0.222695 0.974457 0.028681\n5930 19.369903 -0.025856 -1.027763 1.303023 0.003726 -0.227693 0.972956 0.038706\n5931 19.377931 -0.024841 -1.028851 1.302708 0.014187 -0.232955 0.971209 0.047801\n5932 19.388685 -0.022773 -1.029422 1.302084 0.027247 -0.239994 0.968767 0.056132\n5933 19.397340 -0.022372 -1.030820 1.301689 0.035512 -0.243297 0.966974 0.067134\n5934 19.404818 -0.021192 -1.031500 1.301985 0.044709 -0.246361 0.964923 0.078935\n5935 19.411982 -0.020442 -1.032375 1.301388 0.053574 -0.250002 0.962802 0.087411\n5936 19.420739 -0.018727 -1.032741 1.301484 0.062265 -0.254504 0.960114 0.097635\n5937 19.430291 -0.018070 -1.033144 1.301314 0.067836 -0.257143 0.958170 0.105761\n5938 19.436464 -0.016854 -1.033623 1.300996 0.075407 -0.260488 0.955610 0.115190\n5939 19.445959 -0.015740 -1.033927 1.300708 0.084302 -0.264602 0.952487 0.125090\n5940 19.454192 -0.014153 -1.034916 1.300406 0.093801 -0.268657 0.948962 0.135996\n5941 19.461058 -0.013004 -1.035417 1.300141 0.102335 -0.272244 0.945292 0.147763\n5942 19.469557 -0.012137 -1.035747 1.299940 0.110320 -0.274650 0.941697 0.160014\n5943 19.479310 -0.010501 -1.036618 1.299677 0.120729 -0.277022 0.937318 0.173548\n5944 19.486378 -0.008992 -1.037140 1.299530 0.130350 -0.277810 0.933133 0.187335\n5945 19.496125 -0.007438 -1.037556 1.299357 0.140723 -0.278093 0.928409 0.202284\n5946 19.503683 -0.005740 -1.037923 1.298770 0.151746 -0.278928 0.923121 0.216839\n5947 19.512642 -0.003983 -1.038824 1.298496 0.162796 -0.278288 0.917605 0.232496\n5948 19.519462 -0.002512 -1.038928 1.298095 0.173317 -0.277434 0.912160 0.246891\n5949 19.529292 -0.000906 -1.039693 1.297942 0.184434 -0.276599 0.905746 0.262871\n5950 19.537433 0.000138 -1.040218 1.297629 0.194668 -0.275350 0.899558 0.277636\n5951 19.546588 0.001387 -1.040549 1.297184 0.204835 -0.273601 0.893318 0.291837\n5952 19.554189 0.002617 -1.041296 1.296915 0.213650 -0.272253 0.886371 0.307536\n5953 19.561531 0.003951 -1.041670 1.296570 0.221822 -0.269672 0.879894 0.322269\n5954 19.573770 0.004668 -1.041864 1.296310 0.229450 -0.265943 0.874095 0.335539\n5955 19.578789 0.005949 -1.042261 1.295956 0.237821 -0.262673 0.867616 0.348835\n5956 19.587588 0.006950 -1.042672 1.295468 0.244703 -0.257885 0.861977 0.361403\n5957 19.596703 0.007854 -1.042368 1.295357 0.251445 -0.252000 0.856131 0.374581\n5958 19.602983 0.009000 -1.042734 1.294981 0.257380 -0.246577 0.851103 0.385461\n5959 19.612612 0.010335 -1.042943 1.294561 0.264159 -0.240630 0.845612 0.396558\n5960 19.620917 0.011472 -1.043294 1.294125 0.271923 -0.235097 0.839695 0.407061\n5961 19.630104 0.012719 -1.043364 1.293550 0.277833 -0.228329 0.834198 0.418078\n5962 19.637582 0.013858 -1.043799 1.293209 0.285376 -0.221566 0.827878 0.429054\n5963 19.646002 0.015269 -1.044268 1.292713 0.293906 -0.214619 0.820978 0.439948\n5964 19.654157 0.016848 -1.044427 1.292139 0.301522 -0.207381 0.813880 0.451306\n5965 19.662752 0.018288 -1.044717 1.291623 0.309626 -0.199227 0.806707 0.462238\n5966 19.669671 0.019700 -1.045017 1.291099 0.318107 -0.189733 0.799601 0.472703\n5967 19.678871 0.020893 -1.045218 1.290566 0.325548 -0.179926 0.792376 0.483514\n5968 19.688188 0.022229 -1.045369 1.290095 0.331301 -0.170525 0.784812 0.495209\n5969 19.694959 0.023490 -1.045560 1.289505 0.341992 -0.158655 0.776415 0.505025\n5970 19.702788 0.024853 -1.045263 1.288740 0.350016 -0.148519 0.768758 0.514239\n5971 19.712367 0.025634 -1.045448 1.288663 0.357206 -0.134777 0.760115 0.525799\n5972 19.719528 0.026581 -1.045801 1.288184 0.364311 -0.126085 0.751163 0.535850\n5973 19.727819 0.027501 -1.045684 1.287872 0.369935 -0.114704 0.742739 0.546196\n5974 19.738056 0.028473 -1.045797 1.287451 0.376153 -0.104545 0.733929 0.555813\n5975 19.745143 0.029487 -1.045532 1.287182 0.381248 -0.093109 0.725269 0.565656\n5976 19.754134 0.030641 -1.045357 1.286764 0.385974 -0.082301 0.717413 0.574081\n5977 19.762893 0.031331 -1.044728 1.287067 0.389977 -0.070274 0.710560 0.581450\n5978 19.769652 0.033110 -1.044356 1.286386 0.396730 -0.057412 0.702352 0.588227\n5979 19.779631 0.034237 -1.043773 1.286330 0.400688 -0.042931 0.695373 0.595032\n5980 19.786972 0.035739 -1.043452 1.286101 0.407238 -0.031133 0.689076 0.598634\n5981 19.796416 0.036827 -1.043135 1.285915 0.409821 -0.017485 0.683809 0.603445\n5982 19.803782 0.037962 -1.042266 1.285853 0.411899 -0.001711 0.679706 0.606907\n5983 19.811242 0.039142 -1.041781 1.285501 0.415997 0.010803 0.674179 0.610174\n5984 19.820061 0.040488 -1.041752 1.284578 0.421027 0.022615 0.668281 0.612883\n5985 19.830543 0.041683 -1.040724 1.284497 0.424796 0.037279 0.661856 0.616527\n5986 19.836437 0.043495 -1.039513 1.284260 0.425503 0.053405 0.656969 0.620070\n5987 19.846627 0.045056 -1.038599 1.283836 0.427957 0.068085 0.651379 0.622834\n5988 19.854393 0.046476 -1.037953 1.283440 0.431780 0.081133 0.644573 0.625707\n5989 19.861673 0.048018 -1.036199 1.283706 0.432280 0.096701 0.640734 0.627091\n5990 19.871865 0.049268 -1.035839 1.282719 0.439330 0.110649 0.631457 0.629292\n5991 19.878517 0.050597 -1.034467 1.283071 0.437107 0.124023 0.626980 0.632813\n5992 19.887615 0.051675 -1.033668 1.282844 0.440148 0.134760 0.620898 0.634504\n5993 19.895989 0.053194 -1.031995 1.282741 0.441608 0.147221 0.615063 0.636401\n5994 19.902931 0.054438 -1.030842 1.282273 0.448083 0.158854 0.607170 0.636657\n5995 19.911968 0.056088 -1.029439 1.282257 0.448352 0.168087 0.602499 0.638532\n5996 19.921055 0.057821 -1.027850 1.282070 0.448866 0.178087 0.598455 0.639262\n5997 19.928191 0.059347 -1.026261 1.281798 0.450126 0.187943 0.595099 0.638687\n5998 19.936140 0.061305 -1.024541 1.281541 0.452536 0.199674 0.591612 0.636661\n5999 19.945668 0.062568 -1.022808 1.281354 0.452385 0.209935 0.589665 0.635272\n6000 19.953848 0.063860 -1.020879 1.281243 0.453268 0.221135 0.587513 0.632832\n6001 19.961288 0.064860 -1.018736 1.281116 0.451767 0.231875 0.586403 0.631088\n6002 19.970060 0.066506 -1.016881 1.281051 0.452670 0.245423 0.585185 0.626432\n6003 19.979101 0.067193 -1.014500 1.281014 0.448831 0.254610 0.585587 0.625149\n6004 19.987230 0.068645 -1.012119 1.280972 0.447589 0.266769 0.585735 0.620816\n6005 19.996092 0.069810 -1.009567 1.281108 0.443119 0.277576 0.587526 0.617584\n6006 20.004417 0.070550 -1.006768 1.280980 0.436729 0.286305 0.590296 0.615507\n6007 20.011652 0.071036 -1.003828 1.280664 0.428332 0.300715 0.594608 0.610363\n6008 20.021829 0.071806 -1.001529 1.280536 0.427018 0.309093 0.597322 0.604420\n6009 20.029113 0.073115 -0.997894 1.279976 0.418755 0.323147 0.602298 0.597877\n6010 20.037659 0.073770 -0.995014 1.280264 0.412195 0.333306 0.608081 0.590966\n6011 20.046471 0.074561 -0.992627 1.280133 0.405878 0.343059 0.613032 0.584606\n6012 20.053146 0.075147 -0.989962 1.280293 0.399913 0.352857 0.617470 0.578180\n6013 20.062705 0.075050 -0.986595 1.280608 0.389668 0.362761 0.626047 0.569762\n6014 20.070975 0.075534 -0.984261 1.280053 0.380506 0.372181 0.633661 0.561400\n6015 20.077920 0.075751 -0.980770 1.280863 0.372398 0.378189 0.641116 0.554313\n6016 20.086615 0.075794 -0.977636 1.280734 0.364112 0.386201 0.648589 0.545530\n6017 20.096604 0.075879 -0.974630 1.281034 0.353989 0.392518 0.658102 0.536212\n6018 20.103165 0.075651 -0.971561 1.280887 0.346123 0.399845 0.666197 0.525836\n6019 20.112575 0.075774 -0.968477 1.280759 0.338130 0.406462 0.674402 0.515402\n6020 20.120053 0.075668 -0.965071 1.280572 0.329836 0.413565 0.683150 0.503467\n6021 20.129019 0.075368 -0.962412 1.280667 0.321538 0.420640 0.690735 0.492504\n6022 20.136285 0.074628 -0.959388 1.280592 0.314492 0.427016 0.698319 0.480733\n6023 20.146011 0.074763 -0.957150 1.280551 0.305980 0.433921 0.704713 0.470604\n6024 20.153765 0.074136 -0.954049 1.280526 0.297881 0.440363 0.711870 0.458899\n6025 20.164575 0.073352 -0.951176 1.280915 0.289136 0.445414 0.719532 0.447526\n6026 20.170493 0.072058 -0.947998 1.280690 0.280745 0.450988 0.727135 0.434818\n6027 20.178113 0.071809 -0.945878 1.280663 0.272060 0.455283 0.733229 0.425531\n6028 20.187911 0.070955 -0.943167 1.280998 0.262837 0.458251 0.740177 0.416006\n6029 20.194935 0.070024 -0.940431 1.280903 0.253712 0.461734 0.747048 0.405402\n6030 20.204337 0.068918 -0.937574 1.281012 0.244220 0.464366 0.753927 0.395366\n6031 20.212576 0.067675 -0.934849 1.280869 0.233717 0.467065 0.761694 0.383469\n6032 20.219626 0.066266 -0.931871 1.281118 0.224562 0.469130 0.768197 0.373312\n6033 20.229369 0.064941 -0.929358 1.281933 0.214304 0.471040 0.774692 0.363383\n6034 20.237248 0.063444 -0.926740 1.281935 0.203162 0.472993 0.782484 0.350318\n6035 20.247452 0.061864 -0.924340 1.282320 0.192174 0.474034 0.789967 0.338102\n6036 20.254160 0.060441 -0.922134 1.282568 0.181644 0.473968 0.797911 0.325114\n6037 20.262346 0.058512 -0.920242 1.282938 0.171936 0.473601 0.805184 0.312761\n6038 20.270762 0.057053 -0.918241 1.283042 0.162419 0.473449 0.811505 0.301540\n6039 20.279566 0.055183 -0.916346 1.283702 0.149939 0.472488 0.820094 0.285867\n6040 20.287385 0.053589 -0.914904 1.283935 0.137673 0.470855 0.827600 0.272800\n6041 20.297839 0.051022 -0.913541 1.284686 0.129942 0.468083 0.834188 0.261045\n6042 20.304048 0.048663 -0.911159 1.285511 0.116939 0.462838 0.843655 0.245668\n6043 20.311416 0.046551 -0.910148 1.286100 0.105832 0.463324 0.848886 0.231352\n6044 20.319353 0.043943 -0.908990 1.286476 0.094942 0.459242 0.856450 0.215814\n6045 20.327832 0.041134 -0.908588 1.286403 0.081129 0.456928 0.862462 0.201977\n6046 20.339674 0.039073 -0.907184 1.288203 0.071334 0.452977 0.868057 0.190265\n6047 20.345748 0.036721 -0.906170 1.287864 0.058754 0.447747 0.874406 0.177442\n6048 20.355358 0.034731 -0.906012 1.289357 0.048497 0.441768 0.880722 0.163765\n6049 20.361651 0.032136 -0.905944 1.290161 0.037176 0.435499 0.886608 0.151274\n6050 20.369482 0.029464 -0.905175 1.290758 0.026647 0.429695 0.891785 0.139186\n6051 20.378312 0.026848 -0.905174 1.291988 0.015785 0.425272 0.895910 0.127439\n6052 20.387357 0.024280 -0.905154 1.292887 0.007496 0.417554 0.901330 0.114879\n6053 20.396224 0.021860 -0.905747 1.294030 -0.004718 0.409130 0.906635 0.102973\n6054 20.402907 0.018764 -0.905489 1.294443 -0.013625 0.401831 0.911230 0.089477\n6055 20.412759 0.015587 -0.905559 1.295834 -0.025505 0.393624 0.915709 0.076730\n6056 20.419805 0.012994 -0.906234 1.296270 -0.037821 0.387015 0.919044 0.064393\n6057 20.429138 0.010946 -0.907199 1.297318 -0.044658 0.379747 0.922565 0.051691\n6058 20.437015 0.007834 -0.907666 1.297816 -0.059403 0.370556 0.926005 0.040927\n6059 20.444582 0.005209 -0.908711 1.298514 -0.069239 0.363206 0.928696 0.028484\n6060 20.452951 0.002924 -0.910024 1.299019 -0.076301 0.356736 0.930925 0.017193\n6061 20.462512 0.001578 -0.911073 1.299718 -0.090183 0.346783 0.933562 0.008396\n6062 20.469739 -0.001458 -0.911807 1.300602 -0.101607 0.341286 0.934438 -0.005076\n6063 20.478051 -0.004196 -0.912903 1.301205 -0.110590 0.333961 0.935941 -0.015953\n6064 20.488284 -0.006041 -0.914158 1.301327 -0.116800 0.328091 0.937082 -0.024304\n6065 20.494849 -0.009008 -0.915433 1.301554 -0.125224 0.319908 0.938573 -0.032523\n6066 20.502900 -0.010869 -0.916907 1.301760 -0.134600 0.312194 0.939547 -0.040846\n6067 20.512248 -0.013227 -0.918285 1.302254 -0.146478 0.306135 0.939345 -0.049557\n6068 20.520864 -0.016709 -0.918701 1.301985 -0.151849 0.302203 0.939307 -0.057600\n6069 20.528014 -0.017312 -0.921355 1.303051 -0.155410 0.291401 0.941816 -0.062575\n6070 20.536106 -0.019296 -0.922293 1.303545 -0.165001 0.283573 0.942217 -0.067734\n6071 20.544762 -0.021213 -0.924609 1.304278 -0.165325 0.274611 0.944324 -0.074218\n6072 20.554756 -0.022606 -0.925470 1.304478 -0.169308 0.268202 0.945127 -0.078344\n6073 20.562122 -0.024159 -0.926877 1.304713 -0.173298 0.259850 0.946344 -0.082942\n6074 20.571331 -0.025605 -0.928548 1.304866 -0.177848 0.251192 0.947561 -0.086033\n6075 20.578406 -0.027028 -0.930059 1.305066 -0.179331 0.244108 0.948829 -0.089306\n6076 20.587977 -0.027989 -0.931978 1.305692 -0.180447 0.236009 0.950519 -0.090843\n6077 20.596093 -0.029694 -0.932877 1.306021 -0.181985 0.231809 0.951114 -0.092352\n6078 20.603197 -0.030717 -0.934289 1.306243 -0.183015 0.224317 0.952582 -0.093672\n6079 20.613076 -0.031670 -0.936048 1.306583 -0.182584 0.217902 0.954077 -0.094440\n6080 20.620049 -0.032806 -0.937365 1.306837 -0.183199 0.211583 0.955320 -0.095052\n6081 20.627859 -0.033889 -0.938338 1.306808 -0.186246 0.204922 0.956217 -0.094699\n6082 20.636431 -0.034710 -0.939817 1.307187 -0.182432 0.198095 0.958373 -0.094862\n6083 20.646551 -0.035399 -0.941473 1.307103 -0.183754 0.189968 0.959833 -0.094167\n6084 20.652982 -0.035547 -0.943584 1.308050 -0.183558 0.181429 0.961511 -0.094268\n6085 20.661505 -0.036372 -0.944670 1.307939 -0.180840 0.173132 0.963772 -0.092011\n6086 20.670279 -0.037909 -0.946307 1.307477 -0.184270 0.161678 0.965385 -0.089083\n6087 20.677960 -0.038333 -0.947680 1.308002 -0.175061 0.151042 0.969134 -0.085553\n6088 20.687289 -0.038986 -0.949204 1.308096 -0.170127 0.141211 0.971730 -0.082802\n6089 20.694961 -0.039256 -0.950535 1.308154 -0.172006 0.126024 0.973612 -0.081307\n6090 20.704279 -0.040090 -0.952225 1.308439 -0.169742 0.117449 0.975471 -0.076489\n6091 20.712767 -0.040565 -0.954298 1.308471 -0.166739 0.105813 0.977514 -0.073949\n6092 20.720060 -0.041335 -0.955904 1.308218 -0.164120 0.096219 0.979177 -0.070848\n6093 20.727994 -0.041857 -0.957688 1.308282 -0.162104 0.083474 0.980916 -0.067516\n6094 20.737788 -0.042365 -0.959791 1.308253 -0.158165 0.072707 0.982616 -0.064520\n6095 20.745569 -0.042108 -0.961935 1.308543 -0.153893 0.059355 0.984514 -0.059378\n6096 20.754046 -0.043502 -0.963799 1.308259 -0.157203 0.052351 0.984439 -0.058545\n6097 20.762682 -0.043652 -0.965661 1.308295 -0.153541 0.042565 0.985681 -0.055192\n6098 20.770203 -0.043827 -0.967757 1.308290 -0.150217 0.032625 0.986721 -0.052470\n6099 20.779043 -0.043851 -0.969966 1.308307 -0.147082 0.022337 0.987655 -0.049051\n6100 20.786818 -0.044200 -0.971986 1.308204 -0.145515 0.012554 0.988197 -0.046195\n6101 20.794456 -0.044020 -0.973800 1.308205 -0.141067 0.001747 0.989089 -0.042425\n6102 20.802874 -0.044292 -0.975175 1.307962 -0.139456 -0.008202 0.989427 -0.038971\n6103 20.812765 -0.044154 -0.977154 1.308050 -0.133776 -0.018933 0.990218 -0.034854\n6104 20.819720 -0.043784 -0.978577 1.308209 -0.127022 -0.029485 0.990995 -0.030405\n6105 20.828100 -0.043759 -0.979852 1.308124 -0.122704 -0.038847 0.991360 -0.025308\n6106 20.837671 -0.043175 -0.981035 1.308196 -0.115237 -0.047160 0.992030 -0.019314\n6107 20.845698 -0.042794 -0.982432 1.308192 -0.108308 -0.055490 0.992471 -0.013821\n6108 20.852927 -0.042213 -0.984201 1.308216 -0.100318 -0.063718 0.992884 -0.007648\n6109 20.861410 -0.041740 -0.985718 1.308178 -0.092969 -0.071855 0.993070 -0.002363\n6110 20.871188 -0.041551 -0.987347 1.308079 -0.087523 -0.079044 0.993015 0.003537\n6111 20.879016 -0.041251 -0.988330 1.307825 -0.082293 -0.085620 0.992859 0.011294\n6112 20.887882 -0.040598 -0.990065 1.307749 -0.073773 -0.093061 0.992797 0.015856\n6113 20.895321 -0.040552 -0.991508 1.307469 -0.070783 -0.098473 0.992374 0.022062\n6114 20.904153 -0.039810 -0.993208 1.307383 -0.064859 -0.105138 0.991978 0.026803\n6115 20.913275 -0.039063 -0.994659 1.307158 -0.059219 -0.110185 0.991564 0.033947\n6116 20.919988 -0.038508 -0.995984 1.306884 -0.052621 -0.114479 0.991148 0.041838\n6117 20.928500 -0.037580 -0.997494 1.306821 -0.047130 -0.118565 0.990589 0.049551\n6118 20.937046 -0.036812 -0.998956 1.306553 -0.042242 -0.122385 0.989885 0.058014\n6119 20.944774 -0.036268 -1.000116 1.306229 -0.036821 -0.125958 0.988970 0.068680\n6120 20.954011 -0.035307 -1.001981 1.305782 -0.031331 -0.129712 0.988224 0.074877\n6121 20.962148 -0.034532 -1.003598 1.305313 -0.025309 -0.132261 0.987448 0.082536\n6122 20.970795 -0.033684 -1.005295 1.304944 -0.017324 -0.136374 0.986380 0.090317\n6123 20.979305 -0.033072 -1.006900 1.304392 -0.011832 -0.140010 0.985292 0.097242\n6124 20.986450 -0.032826 -1.008054 1.303817 -0.008612 -0.141783 0.984294 0.104831\n6125 20.994484 -0.032052 -1.009776 1.303385 -0.001605 -0.144255 0.983517 0.109005\n6126 21.004653 -0.031829 -1.011301 1.302389 -0.000379 -0.145235 0.982737 0.114612\n6127 21.012514 -0.031257 -1.012498 1.301878 0.006939 -0.145931 0.982004 0.119686\n6128 21.020697 -0.030505 -1.013643 1.301079 0.010834 -0.146980 0.981290 0.123893\n6129 21.029268 -0.030370 -1.014859 1.300481 0.013215 -0.145117 0.981144 0.126978\n6130 21.036219 -0.030082 -1.015874 1.299790 0.015782 -0.142589 0.981178 0.129267\n6131 21.045807 -0.030126 -1.016959 1.299032 0.015773 -0.138636 0.981505 0.131072\n6132 21.053831 -0.029878 -1.017771 1.298153 0.019013 -0.136117 0.981563 0.132835\n6133 21.061172 -0.029729 -1.018530 1.297542 0.019160 -0.132150 0.981952 0.133940\n6134 21.069576 -0.030144 -1.019197 1.296644 0.017766 -0.127599 0.982465 0.134781\n6135 21.079789 -0.030032 -1.019589 1.295704 0.015352 -0.122739 0.982908 0.136348\n6136 21.086320 -0.029525 -1.019817 1.294914 0.017307 -0.119193 0.983249 0.136804\n6137 21.095094 -0.029827 -1.020042 1.294048 0.015324 -0.113040 0.983777 0.138459\n6138 21.104323 -0.029857 -1.020045 1.293198 0.013059 -0.106466 0.984324 0.140006\n6139 21.111329 -0.029898 -1.020059 1.292491 0.014631 -0.097675 0.984987 0.141582\n6140 21.120777 -0.030134 -1.019762 1.291845 0.010038 -0.088390 0.985688 0.143195\n6141 21.128639 -0.029548 -1.019355 1.291306 0.010998 -0.079047 0.986075 0.145902\n6142 21.136543 -0.029786 -1.019009 1.290672 0.008133 -0.067178 0.986762 0.147383\n6143 21.146849 -0.029734 -1.018702 1.289972 0.006066 -0.055476 0.987274 0.148913\n6144 21.153565 -0.029185 -1.018181 1.289549 0.009050 -0.044133 0.987510 0.150981\n6145 21.162767 -0.028501 -1.017426 1.289170 0.008592 -0.032514 0.987590 0.153411\n6146 21.171112 -0.027898 -1.016733 1.288717 0.008372 -0.020823 0.987501 0.156009\n6147 21.180003 -0.026614 -1.016064 1.288581 0.012482 -0.012029 0.987085 0.159255\n6148 21.186684 -0.026148 -1.015278 1.288366 0.014015 -0.002309 0.986832 0.161125\n6149 21.194611 -0.025294 -1.013777 1.288220 0.014996 0.008139 0.986438 0.163244\n6150 21.204209 -0.024404 -1.013078 1.288248 0.019059 0.016352 0.985762 0.166263\n6151 21.213325 -0.023324 -1.012274 1.288166 0.022861 0.024647 0.985040 0.169017\n6152 21.219899 -0.022223 -1.010792 1.288440 0.026605 0.032415 0.984216 0.171931\n6153 21.229139 -0.021328 -1.009776 1.288819 0.028240 0.039623 0.983438 0.174589\n6154 21.236653 -0.020045 -1.008443 1.289099 0.034398 0.046897 0.982278 0.178178\n6155 21.244532 -0.018472 -1.007578 1.289622 0.043374 0.053640 0.981250 0.179972\n6156 21.254164 -0.016911 -1.006267 1.290198 0.049718 0.060633 0.980133 0.182185\n6157 21.262376 -0.015234 -1.005014 1.290857 0.057969 0.067726 0.978862 0.184071\n6158 21.270777 -0.014126 -1.003543 1.291590 0.065565 0.074868 0.977642 0.185236\n6159 21.278309 -0.012502 -1.002325 1.292381 0.076972 0.082514 0.975867 0.186950\n6160 21.286916 -0.011317 -1.000448 1.293201 0.084069 0.088635 0.974309 0.189204\n6161 21.294484 -0.009890 -0.999589 1.294011 0.092802 0.094997 0.972536 0.191146\n6162 21.303953 -0.008028 -0.998373 1.295271 0.099285 0.100245 0.970851 0.193756\n6163 21.312277 -0.006571 -0.997012 1.296216 0.107381 0.105288 0.968637 0.197804\n6164 21.320822 -0.004792 -0.995659 1.297026 0.115628 0.109488 0.966247 0.202507\n6165 21.330987 -0.002975 -0.994452 1.297643 0.122046 0.113210 0.963991 0.207390\n6166 21.336448 -0.000996 -0.993157 1.298417 0.134435 0.117819 0.960227 0.214498\n6167 21.346389 0.001045 -0.991984 1.298940 0.146344 0.121629 0.956330 0.221861\n6168 21.353292 0.003295 -0.990661 1.299055 0.159844 0.127280 0.951669 0.229292\n6169 21.361355 0.005905 -0.989432 1.299776 0.173130 0.133234 0.946535 0.237373\n6170 21.369477 0.007785 -0.987739 1.300410 0.179395 0.136304 0.942284 0.247669\n6171 21.379830 0.010251 -0.986679 1.300698 0.191057 0.145530 0.936473 0.255611\n6172 21.386819 0.012177 -0.985831 1.300678 0.206026 0.150176 0.929299 0.267213\n6173 21.394733 0.015907 -0.984681 1.300652 0.223873 0.156568 0.921682 0.275446\n6174 21.404750 0.019247 -0.983514 1.300735 0.240756 0.163445 0.913223 0.285213\n6175 21.411937 0.023222 -0.982234 1.300606 0.258150 0.170257 0.904068 0.295012\n6176 21.420886 0.025548 -0.981594 1.300316 0.270740 0.178232 0.896368 0.302419\n6177 21.430113 0.028944 -0.980935 1.299738 0.287648 0.186021 0.887323 0.308728\n6178 21.436845 0.032047 -0.980032 1.299286 0.302985 0.193549 0.878029 0.315917\n6179 21.445531 0.035343 -0.979816 1.298612 0.318580 0.199612 0.867954 0.324525\n6180 21.453682 0.037923 -0.979125 1.297690 0.331396 0.205804 0.858917 0.331788\n6181 21.461189 0.041366 -0.978799 1.296905 0.348518 0.210313 0.847539 0.340561\n6182 21.470807 0.044277 -0.978634 1.295504 0.360581 0.213774 0.838137 0.349011\n6183 21.478150 0.047347 -0.978377 1.294532 0.374252 0.218069 0.826855 0.358736\n6184 21.487394 0.050397 -0.978479 1.293290 0.388389 0.220889 0.814993 0.368983\n6185 21.495073 0.053390 -0.978390 1.291870 0.400999 0.224677 0.803695 0.377883\n6186 21.503707 0.056642 -0.977743 1.290249 0.412811 0.230640 0.791990 0.386193\n6187 21.511147 0.059292 -0.978820 1.288915 0.425435 0.233262 0.781349 0.392540\n6188 21.520796 0.061800 -0.977855 1.287677 0.436021 0.239502 0.768998 0.401456\n6189 21.528560 0.064053 -0.978128 1.286504 0.446693 0.245916 0.757306 0.408017\n6190 21.537687 0.066729 -0.978380 1.284835 0.456508 0.251079 0.746198 0.414426\n6191 21.546794 0.068915 -0.978137 1.283299 0.467178 0.256172 0.733661 0.421736\n6192 21.553625 0.071238 -0.977875 1.282157 0.476096 0.259454 0.722663 0.428690\n6193 21.561236 0.072988 -0.977642 1.281032 0.482523 0.265472 0.711761 0.435997\n6194 21.569526 0.074749 -0.977509 1.280013 0.489718 0.271155 0.701383 0.441264\n6195 21.577859 0.076403 -0.977245 1.278968 0.496225 0.275973 0.691847 0.446034\n6196 21.587882 0.077617 -0.977020 1.278352 0.500444 0.281058 0.684231 0.449878\n6197 21.595102 0.078962 -0.976780 1.277663 0.504966 0.284917 0.676841 0.453561\n6198 21.603786 0.079957 -0.976830 1.277038 0.506965 0.287857 0.671966 0.456713\n6199 21.613252 0.080663 -0.976487 1.276234 0.507440 0.290556 0.668568 0.459455\n6200 21.620703 0.081358 -0.976020 1.276381 0.507067 0.291612 0.666471 0.462236\n6201 21.629538 0.081709 -0.975280 1.276214 0.506306 0.292768 0.666306 0.462577\n6202 21.636777 0.081822 -0.974938 1.276437 0.504395 0.293794 0.667193 0.462736\n6203 21.644824 0.081755 -0.974309 1.277131 0.501200 0.293576 0.670285 0.461876\n6204 21.653770 0.081783 -0.973092 1.277857 0.496987 0.293608 0.675385 0.458970\n6205 21.661558 0.081384 -0.972006 1.278269 0.492884 0.294232 0.680761 0.455036\n6206 21.670251 0.081060 -0.971668 1.279437 0.486443 0.292679 0.688005 0.452064\n6207 21.677741 0.079732 -0.971051 1.280384 0.479929 0.293235 0.696110 0.446220\n6208 21.687306 0.078758 -0.969762 1.281288 0.473163 0.291757 0.704894 0.440589\n6209 21.695263 0.077320 -0.969329 1.282658 0.466235 0.290726 0.713871 0.434156\n6210 21.704133 0.076011 -0.968053 1.283999 0.458538 0.289971 0.723501 0.426856\n6211 21.712121 0.074042 -0.968049 1.285509 0.448545 0.287907 0.735483 0.418308\n6212 21.720899 0.072904 -0.967344 1.286641 0.441022 0.284513 0.744828 0.412048\n6213 21.727880 0.070819 -0.965691 1.288096 0.432198 0.281083 0.755899 0.403503\n6214 21.737701 0.068620 -0.965906 1.289471 0.422100 0.276431 0.767776 0.394888\n6215 21.744525 0.066258 -0.965377 1.290956 0.410655 0.272440 0.779968 0.385731\n6216 21.753952 0.063581 -0.965759 1.292551 0.399338 0.267515 0.791981 0.376473\n6217 21.762843 0.060346 -0.964548 1.294493 0.387856 0.262314 0.803981 0.366570\n6218 21.770313 0.056973 -0.963844 1.296212 0.374804 0.256781 0.816149 0.357051\n6219 21.779006 0.053816 -0.963849 1.297870 0.360410 0.251321 0.827799 0.348843\n6220 21.787125 0.050345 -0.963433 1.299545 0.345347 0.245076 0.840271 0.338553\n6221 21.794832 0.046640 -0.963455 1.301222 0.328152 0.238617 0.852984 0.328325\n6222 21.802931 0.042791 -0.963657 1.302402 0.312844 0.231006 0.864901 0.317351\n6223 21.811868 0.039047 -0.963950 1.303746 0.300311 0.224468 0.874574 0.307488\n6224 21.820758 0.035301 -0.964237 1.305176 0.282491 0.215933 0.886461 0.296240\n6225 21.827962 0.031470 -0.964565 1.305741 0.261442 0.207832 0.898663 0.284356\n6226 21.837457 0.026907 -0.965061 1.307600 0.245589 0.199047 0.907994 0.274977\n6227 21.844860 0.022831 -0.965727 1.308577 0.227590 0.190512 0.917716 0.264019\n6228 21.854125 0.018619 -0.966618 1.309521 0.209536 0.181867 0.926741 0.253320\n6229 21.861661 0.013803 -0.967728 1.310157 0.191831 0.173514 0.935033 0.242501\n6230 21.870437 0.009808 -0.968595 1.311195 0.169646 0.164348 0.943500 0.232417\n6231 21.877873 0.005600 -0.970049 1.311611 0.155575 0.156144 0.949996 0.221188\n6232 21.887589 0.001048 -0.971570 1.311985 0.137466 0.148349 0.956195 0.211628\n6233 21.895140 -0.003238 -0.972980 1.312374 0.119820 0.141395 0.961419 0.203283\n6234 21.904109 -0.007873 -0.974648 1.313131 0.098104 0.132843 0.967419 0.191909\n6235 21.911899 -0.011724 -0.976207 1.313147 0.083668 0.126029 0.971478 0.182610\n6236 21.920395 -0.016571 -0.977825 1.312990 0.065401 0.119125 0.975345 0.173881\n6237 21.929028 -0.020791 -0.979469 1.312853 0.049965 0.112766 0.978494 0.165338\n6238 21.937210 -0.024947 -0.981256 1.312683 0.034407 0.106033 0.981310 0.156858\n6239 21.944912 -0.028868 -0.983194 1.312421 0.021274 0.098769 0.983710 0.148687\n6240 21.952923 -0.033182 -0.984811 1.311914 0.005077 0.092667 0.985709 0.140591\n6241 21.961910 -0.037227 -0.986721 1.311397 -0.009475 0.086165 0.987349 0.132769\n6242 21.970756 -0.040905 -0.988785 1.310808 -0.018343 0.079491 0.988727 0.125551\n6243 21.977871 -0.045326 -0.990496 1.310064 -0.037660 0.073120 0.989542 0.118501\n6244 21.987377 -0.048293 -0.992508 1.309307 -0.045543 0.065589 0.990499 0.111961\n6245 21.994961 -0.052026 -0.994553 1.308279 -0.058361 0.059521 0.990897 0.105712\n6246 22.004025 -0.056078 -0.996325 1.307264 -0.076779 0.052698 0.990657 0.099632\n6247 22.011929 -0.059406 -0.998794 1.306274 -0.085110 0.044969 0.990924 0.093830\n6248 22.020780 -0.062923 -1.000766 1.305059 -0.097636 0.038016 0.990598 0.087961\n6249 22.027864 -0.066918 -1.002951 1.303561 -0.115438 0.033143 0.989361 0.082097\n6250 22.038594 -0.070273 -1.004987 1.302452 -0.125950 0.025028 0.988750 0.076702\n6251 22.045036 -0.073690 -1.006971 1.300901 -0.139264 0.019118 0.987457 0.071902\n6252 22.054104 -0.076692 -1.008891 1.299416 -0.149819 0.013259 0.986357 0.066921\n6253 22.061972 -0.079298 -1.012130 1.297798 -0.159222 0.006339 0.985214 0.062949\n6254 22.070877 -0.082171 -1.013133 1.296184 -0.168862 0.000269 0.983911 0.058350\n6255 22.079083 -0.085461 -1.015024 1.294573 -0.183375 -0.004966 0.981561 0.053724\n6256 22.087237 -0.087958 -1.017066 1.292810 -0.191638 -0.011398 0.980117 0.050147\n6257 22.094695 -0.090317 -1.018939 1.291249 -0.203295 -0.015695 0.977869 0.046875\n6258 22.103106 -0.093241 -1.020627 1.289597 -0.214914 -0.022750 0.975418 0.043061\n6259 22.111982 -0.095532 -1.022321 1.287938 -0.224003 -0.027519 0.973334 0.041073\n6260 22.120891 -0.098117 -1.023580 1.286280 -0.233180 -0.032558 0.971102 0.039084\n6261 22.127902 -0.100522 -1.025153 1.284614 -0.242520 -0.037180 0.968733 0.036851\n6262 22.137530 -0.102483 -1.026543 1.283081 -0.249719 -0.041888 0.966762 0.035446\n6263 22.144817 -0.103634 -1.027914 1.281125 -0.260478 -0.050379 0.963610 0.032696\n6264 22.153998 -0.105374 -1.028828 1.280570 -0.264966 -0.054065 0.962099 0.035139\n6265 22.162043 -0.107527 -1.029881 1.278550 -0.272388 -0.059579 0.959744 0.033854\n6266 22.170847 -0.109373 -1.031307 1.277537 -0.275954 -0.064374 0.958476 0.032081\n6267 22.177944 -0.111510 -1.032082 1.276485 -0.282399 -0.068055 0.956294 0.033476\n6268 22.187818 -0.113217 -1.033171 1.275358 -0.286372 -0.070121 0.955036 0.031310\n6269 22.194721 -0.114635 -1.034548 1.274262 -0.285094 -0.069874 0.955384 0.032857\n6270 22.204191 -0.116596 -1.034930 1.273315 -0.290689 -0.072154 0.953501 0.033611\n6271 22.211928 -0.117953 -1.035763 1.272267 -0.290684 -0.072807 0.953512 0.031872\n6272 22.221122 -0.119197 -1.035882 1.271412 -0.288441 -0.072451 0.954005 0.037774\n6273 22.229727 -0.120720 -1.036288 1.270599 -0.290564 -0.073537 0.953184 0.040067\n6274 22.236836 -0.122046 -1.036578 1.269916 -0.292663 -0.074116 0.952386 0.042624\n6275 22.244897 -0.123690 -1.036986 1.269361 -0.295326 -0.076543 0.951225 0.045778\n6276 22.253679 -0.124160 -1.036764 1.268782 -0.292562 -0.077099 0.951819 0.050048\n6277 22.261903 -0.125356 -1.036660 1.268320 -0.293516 -0.077922 0.951241 0.054007\n6278 22.270919 -0.126412 -1.036652 1.267799 -0.294392 -0.079162 0.950733 0.056336\n6279 22.278118 -0.126837 -1.036887 1.267516 -0.291254 -0.079727 0.951326 0.061597\n6280 22.287356 -0.127786 -1.036339 1.267245 -0.291892 -0.080721 0.950825 0.064926\n6281 22.295167 -0.127801 -1.036461 1.266859 -0.288325 -0.080902 0.951566 0.069618\n6282 22.304260 -0.128873 -1.035981 1.266945 -0.289556 -0.081261 0.950692 0.075760\n6283 22.312063 -0.128847 -1.035839 1.266866 -0.284912 -0.080607 0.951832 0.079641\n6284 22.320914 -0.128933 -1.035912 1.266803 -0.281296 -0.078810 0.952540 0.085608\n6285 22.328195 -0.128610 -1.035223 1.267325 -0.276151 -0.079262 0.953502 0.091066\n6286 22.337717 -0.128597 -1.034652 1.267852 -0.271730 -0.076733 0.954153 0.099336\n6287 22.345347 -0.127781 -1.033719 1.269000 -0.267410 -0.071482 0.955269 0.104134\n6288 22.352739 -0.127314 -1.032572 1.269254 -0.261826 -0.072795 0.955597 0.113941\n6289 22.362234 -0.126715 -1.031379 1.270363 -0.255331 -0.068404 0.956562 0.122951\n6290 22.370627 -0.125259 -1.031081 1.271613 -0.239236 -0.062754 0.960096 0.130555\n6291 22.378231 -0.124078 -1.029623 1.273200 -0.230401 -0.055001 0.961355 0.140309\n6292 22.386420 -0.122190 -1.028193 1.274655 -0.218814 -0.050880 0.962674 0.150965\n6293 22.395143 -0.120419 -1.027327 1.275992 -0.208584 -0.044468 0.963930 0.159228\n6294 22.404201 -0.118356 -1.026115 1.277401 -0.195704 -0.038196 0.965037 0.170132\n6295 22.413112 -0.115889 -1.024298 1.279116 -0.184355 -0.030112 0.966093 0.178245\n6296 22.420162 -0.113631 -1.022680 1.280644 -0.170465 -0.021911 0.967006 0.188044\n6297 22.428026 -0.111097 -1.020963 1.282300 -0.158155 -0.013706 0.967639 0.196148\n6298 22.436134 -0.108427 -1.019850 1.283509 -0.142384 -0.003746 0.968395 0.204755\n6299 22.445280 -0.105164 -1.017589 1.285727 -0.128575 0.007532 0.968749 0.211985\n6300 22.454182 -0.102076 -1.016147 1.287426 -0.114832 0.018199 0.969020 0.217904\n6301 22.461344 -0.098898 -1.014355 1.288964 -0.100389 0.029309 0.968773 0.224816\n6302 22.471343 -0.095305 -1.013242 1.290278 -0.086428 0.041778 0.968216 0.230962\n6303 22.478451 -0.092004 -1.010690 1.291962 -0.074304 0.053731 0.967491 0.235699\n6304 22.487218 -0.088389 -1.008996 1.293388 -0.058889 0.064485 0.966472 0.241466\n6305 22.495564 -0.084391 -1.007431 1.294646 -0.043512 0.076072 0.965052 0.246971\n6306 22.504074 -0.080809 -1.005886 1.296034 -0.025750 0.083142 0.963590 0.252820\n6307 22.511961 -0.076782 -1.004686 1.297426 -0.007511 0.089834 0.961255 0.260503\n6308 22.520861 -0.072720 -1.002755 1.298354 0.008181 0.098473 0.958382 0.267844\n6309 22.528171 -0.068173 -1.001487 1.299217 0.031607 0.105604 0.954853 0.275870\n6310 22.536133 -0.064114 -1.000254 1.300046 0.045778 0.110927 0.951406 0.283597\n6311 22.544645 -0.059858 -0.998955 1.300673 0.066680 0.117804 0.946663 0.292413\n6312 22.554064 -0.055485 -0.997979 1.301422 0.080701 0.122410 0.942163 0.301385\n6313 22.562629 -0.051941 -0.996648 1.301524 0.101936 0.130901 0.936415 0.309195\n6314 22.570611 -0.047589 -0.995918 1.301960 0.120552 0.136055 0.930057 0.319298\n6315 22.578742 -0.044078 -0.995012 1.302287 0.136440 0.142866 0.923708 0.328233\n6316 22.587482 -0.040432 -0.993964 1.302202 0.150240 0.149721 0.917651 0.336047\n6317 22.595671 -0.036709 -0.992827 1.302149 0.164713 0.157023 0.910876 0.344265\n6318 22.603370 -0.032926 -0.991968 1.302227 0.177938 0.164142 0.904134 0.352046\n6319 22.611872 -0.029615 -0.991313 1.301770 0.191312 0.172433 0.896668 0.360074\n6320 22.621491 -0.025578 -0.990900 1.301489 0.204102 0.180351 0.889687 0.366431\n6321 22.628556 -0.022699 -0.990101 1.301455 0.208147 0.189026 0.884737 0.371733\n6322 22.636782 -0.019201 -0.989194 1.300453 0.231582 0.198483 0.874274 0.377650\n6323 22.645408 -0.015350 -0.988694 1.300254 0.242409 0.205843 0.867421 0.382685\n6324 22.654104 -0.011759 -0.988000 1.299675 0.254554 0.214412 0.860357 0.386025\n6325 22.661296 -0.009375 -0.986511 1.298202 0.261348 0.227047 0.853468 0.389538\n6326 22.670461 -0.005209 -0.987117 1.297699 0.276652 0.228902 0.847762 0.390343\n6327 22.678724 -0.001727 -0.986122 1.297009 0.289255 0.236475 0.840309 0.392799\n6328 22.686952 0.001747 -0.985538 1.296007 0.303293 0.242415 0.832811 0.394555\n6329 22.695227 0.004884 -0.985589 1.294983 0.315436 0.248251 0.826052 0.395614\n6330 22.704145 0.008488 -0.984705 1.293769 0.331713 0.254600 0.817359 0.396320\n6331 22.711410 0.010971 -0.984089 1.293007 0.342657 0.262672 0.809374 0.398125\n6332 22.721048 0.014402 -0.984161 1.291795 0.357815 0.267615 0.801097 0.398239\n6333 22.729121 0.017322 -0.984185 1.290420 0.370805 0.273336 0.793229 0.398221\n6334 22.737562 0.019677 -0.984142 1.289259 0.382569 0.279188 0.786391 0.396591\n6335 22.745472 0.022460 -0.984401 1.287930 0.395727 0.282973 0.778517 0.396532\n6336 22.754698 0.025246 -0.984416 1.286683 0.409712 0.286134 0.770193 0.396315\n6337 22.762681 0.027168 -0.984972 1.285379 0.418938 0.288693 0.765126 0.394626\n6338 22.770143 0.029997 -0.985347 1.283649 0.431509 0.289600 0.757229 0.395647\n6339 22.777957 0.032523 -0.985176 1.281935 0.444407 0.288343 0.749958 0.396137\n6340 22.787618 0.034480 -0.985822 1.280921 0.454861 0.288237 0.743570 0.396390\n6341 22.795833 0.036602 -0.986893 1.279483 0.466737 0.288202 0.736651 0.395527\n6342 22.804305 0.038929 -0.987747 1.277605 0.479299 0.286927 0.728704 0.396151\n6343 22.814263 0.041198 -0.988880 1.275885 0.491145 0.286247 0.721231 0.395810\n6344 22.820403 0.043340 -0.989290 1.274344 0.504665 0.285253 0.712280 0.395729\n6345 22.828096 0.045292 -0.990287 1.272484 0.517382 0.284900 0.704231 0.393963\n6346 22.839337 0.047434 -0.990502 1.270572 0.529378 0.283670 0.696301 0.393009\n6347 22.844822 0.049027 -0.992017 1.269583 0.542929 0.282779 0.686248 0.392845\n6348 22.853617 0.050634 -0.993081 1.267592 0.554224 0.282288 0.678019 0.391713\n6349 22.862125 0.051663 -0.994343 1.266135 0.566264 0.281247 0.670389 0.388360\n6350 22.870978 0.052884 -0.994650 1.264199 0.575029 0.281360 0.662644 0.388691\n6351 22.880551 0.054583 -0.995479 1.263740 0.588527 0.277860 0.651613 0.389654\n6352 22.887498 0.056207 -0.996458 1.262067 0.598866 0.273590 0.642715 0.391695\n6353 22.894732 0.057328 -0.997043 1.260674 0.608134 0.274362 0.635100 0.389290\n6354 22.903620 0.058700 -0.998109 1.259457 0.617188 0.271084 0.627386 0.389846\n6355 22.912199 0.059781 -0.998545 1.257894 -0.625546 -0.272605 -0.621308 -0.385169\n6356 22.920750 0.061459 -0.999366 1.256249 -0.632289 -0.270937 -0.616784 -0.382596\n6357 22.929439 0.062490 -0.999426 1.254885 -0.639226 -0.270484 -0.611986 -0.379079\n6358 22.937048 0.063645 -0.999670 1.253487 -0.645294 -0.269754 -0.608668 -0.374636\n6359 22.944815 0.064726 -0.999955 1.252212 -0.649731 -0.268943 -0.608135 -0.368364\n6360 22.954965 0.065810 -0.999608 1.251324 -0.654211 -0.268517 -0.607203 -0.362231\n6361 22.961642 0.066917 -1.000011 1.249876 -0.656880 -0.268148 -0.608667 -0.355146\n6362 22.970418 0.067966 -0.999611 1.248190 -0.658877 -0.267827 -0.610933 -0.347722\n6363 22.979819 0.068919 -0.999633 1.247540 -0.659781 -0.267415 -0.614493 -0.339965\n6364 22.987056 0.070054 -0.999339 1.247108 -0.660864 -0.266552 -0.618121 -0.331866\n6365 22.994668 0.070961 -0.998744 1.246691 -0.660075 -0.265712 -0.624772 -0.321495\n6366 23.004121 0.071651 -0.997452 1.244912 -0.657009 -0.266752 -0.631796 -0.313075\n6367 23.011999 0.072942 -0.997269 1.244058 -0.657598 -0.263331 -0.636605 -0.304886\n6368 23.020665 0.073549 -0.996765 1.243580 -0.655227 -0.263765 -0.643392 -0.295215\n6369 23.029240 0.074538 -0.995982 1.243021 -0.655539 -0.260709 -0.648108 -0.286801\n6370 23.037350 0.075240 -0.995336 1.242395 -0.654060 -0.258745 -0.654855 -0.276444\n6371 23.053648 0.075925 -0.994618 1.241916 0.652449 0.257501 0.661335 0.265782\n6372 23.054153 0.076708 -0.993538 1.241606 0.650845 0.255468 0.668163 0.254353\n6373 23.061636 0.077411 -0.993039 1.241048 0.649357 0.254719 0.674156 0.242833\n6374 23.069512 0.077934 -0.991128 1.240877 0.647859 0.253096 0.680150 0.231553\n6375 23.079082 0.078451 -0.990577 1.240427 0.646394 0.252031 0.685911 0.219504\n6376 23.087526 0.079107 -0.989111 1.240257 0.644518 0.251146 0.691736 0.207420\n6377 23.096373 0.079680 -0.988223 1.239967 0.634917 0.251731 0.704302 0.193571\n6378 23.103860 0.080160 -0.987291 1.239476 0.634738 0.251607 0.707720 0.181478\n6379 23.111464 0.080640 -0.985826 1.238982 0.632592 0.250637 0.713372 0.167655\n6380 23.120569 0.081005 -0.985105 1.239603 0.633437 0.249898 0.715959 0.153985\n6381 23.128437 0.081515 -0.983614 1.238576 0.629211 0.249522 0.722313 0.141761\n6382 23.139173 0.081895 -0.982430 1.238229 0.628297 0.248726 0.725876 0.128380\n6383 23.145049 0.082510 -0.981654 1.237614 0.628783 0.247852 0.728140 0.114078\n6384 23.152717 0.082436 -0.979564 1.237624 0.624932 0.246305 0.733938 0.100642\n6385 23.163225 0.082610 -0.978301 1.237750 0.625103 0.245190 0.736024 0.086013\n6386 23.170694 0.082968 -0.977258 1.236943 0.621801 0.242713 0.740905 0.074255\n6387 23.179904 0.082568 -0.975866 1.237160 0.621953 0.240642 0.742715 0.060334\n6388 23.187726 0.083111 -0.974586 1.237085 0.620048 0.239737 0.745616 0.046089\n6389 23.194885 0.082699 -0.973466 1.238062 0.617540 0.236803 0.749391 0.031321\n6390 23.203742 0.083412 -0.972388 1.236896 0.617956 0.235285 0.749881 0.021234\n6391 23.213567 0.083775 -0.971657 1.236593 0.617152 0.232636 0.751610 0.009293\n6392 23.221003 0.083464 -0.970297 1.237092 0.616018 0.229691 0.753497 -0.002346\n6393 23.229381 0.082971 -0.969505 1.236169 0.610799 0.225693 0.758825 -0.013116\n6394 23.237184 0.083044 -0.968001 1.236838 0.615507 0.222361 0.755648 -0.026514\n6395 23.244676 0.083036 -0.967330 1.236741 0.615907 0.219032 0.755883 -0.036391\n6396 23.255787 0.082477 -0.965986 1.238039 0.615128 0.216306 0.756698 -0.047298\n6397 23.262134 0.083518 -0.965568 1.237418 0.617794 0.211291 0.755368 -0.055727\n6398 23.269443 0.083194 -0.965323 1.237015 0.617072 0.210356 0.755317 -0.066848\n6399 23.278828 0.082820 -0.964550 1.236904 0.617975 0.208907 0.754073 -0.076413\n6400 23.287077 0.082566 -0.963768 1.237466 0.617462 0.205903 0.754252 -0.086310\n6401 23.294737 0.082792 -0.963279 1.237198 0.615311 0.201090 0.756428 -0.093659\n6402 23.304018 0.082847 -0.962625 1.237133 0.614670 0.198194 0.756674 -0.101710\n6403 23.312712 0.082136 -0.962286 1.237693 0.613105 0.195176 0.757701 -0.109078\n6404 23.320925 0.082717 -0.961860 1.237578 0.612514 0.191907 0.757696 -0.117882\n6405 23.328317 0.081716 -0.961442 1.238580 0.608822 0.187315 0.760757 -0.124493\n6406 23.335829 0.082094 -0.960970 1.238080 0.606456 0.184268 0.762514 -0.129727\n6407 23.346898 0.082009 -0.960119 1.238483 0.602607 0.182808 0.764704 -0.136653\n6408 23.354670 0.081414 -0.959575 1.239551 0.597634 0.181111 0.767577 -0.144422\n6409 23.362848 0.081664 -0.959668 1.239588 0.591649 0.178536 0.771612 -0.150633\n6410 23.370822 0.081230 -0.959404 1.240369 0.586912 0.176837 0.774381 -0.156835\n6411 23.379432 0.080806 -0.959025 1.241173 0.578436 0.176034 0.779719 -0.162672\n6412 23.387471 0.080248 -0.958575 1.242682 0.573573 0.177080 0.781669 -0.169265\n6413 23.396927 0.079742 -0.958423 1.243307 0.565704 0.174871 0.786632 -0.174954\n6414 23.402980 0.078620 -0.958738 1.244016 0.557553 0.172998 0.791450 -0.181145\n6415 23.412747 0.077293 -0.957434 1.245688 0.549521 0.176213 0.795370 -0.185369\n6416 23.420509 0.078391 -0.956989 1.246412 0.543425 0.173024 0.798740 -0.191745\n6417 23.428263 0.077464 -0.956754 1.247194 0.533189 0.174108 0.803730 -0.198532\n6418 23.437487 0.076378 -0.956251 1.248593 0.521403 0.174608 0.809688 -0.205076\n6419 23.446001 0.074817 -0.955948 1.250217 0.511474 0.176566 0.813930 -0.211510\n6420 23.453512 0.073464 -0.955039 1.251540 0.498976 0.178709 0.819771 -0.216936\n6421 23.461149 0.072627 -0.955212 1.252390 0.490417 0.176953 0.823925 -0.222097\n6422 23.470589 0.071286 -0.954239 1.254487 0.480233 0.180028 0.827813 -0.227357\n6423 23.477898 0.070833 -0.954000 1.255395 0.469333 0.180872 0.832180 -0.233426\n6424 23.487323 0.068759 -0.953453 1.257615 0.456923 0.182329 0.837567 -0.237611\n6425 23.495332 0.066542 -0.952822 1.258658 0.449223 0.180089 0.841222 -0.241064\n6426 23.503799 0.066363 -0.952825 1.260361 0.439438 0.182298 0.844921 -0.244481\n6427 23.511748 0.065189 -0.952410 1.261701 0.428739 0.183712 0.848981 -0.248321\n6428 23.520652 0.063627 -0.952355 1.263202 0.418567 0.183141 0.853429 -0.250839\n6429 23.529807 0.062437 -0.952245 1.264919 0.409987 0.183882 0.856969 -0.252395\n6430 23.538142 0.060760 -0.952213 1.266528 0.396514 0.184568 0.862832 -0.253440\n6431 23.545769 0.059451 -0.952235 1.268074 0.388428 0.184799 0.865753 -0.255822\n6432 23.552730 0.057998 -0.952145 1.269341 0.377820 0.184421 0.870078 -0.257304\n6433 23.563106 0.056588 -0.952198 1.270687 0.367793 0.185280 0.873814 -0.258551\n6434 23.570197 0.055271 -0.952274 1.272173 0.359901 0.185288 0.877050 -0.258695\n6435 23.578639 0.053939 -0.952152 1.273335 0.350387 0.186038 0.880421 -0.259765\n6436 23.587237 0.052433 -0.952064 1.275007 0.340999 0.186599 0.884416 -0.258281\n6437 23.595683 0.051286 -0.951423 1.276455 0.334025 0.189493 0.886584 -0.257854\n6438 23.603672 0.049449 -0.952246 1.277926 0.326526 0.189415 0.889977 -0.255820\n6439 23.613083 0.048288 -0.951862 1.279160 0.318534 0.190500 0.892793 -0.255276\n6440 23.620666 0.046749 -0.951851 1.280479 0.310566 0.192285 0.896020 -0.252433\n6441 23.628123 0.045592 -0.952753 1.281407 0.304215 0.193006 0.899017 -0.248940\n6442 23.638080 0.043559 -0.952640 1.283118 0.296896 0.189378 0.903241 -0.245245\n6443 23.645677 0.042413 -0.953054 1.284386 0.289375 0.193089 0.905986 -0.241180\n6444 23.652851 0.040608 -0.953340 1.285740 0.280619 0.190305 0.910825 -0.235447\n6445 23.662641 0.039625 -0.953728 1.286460 0.274108 0.190014 0.914460 -0.229177\n6446 23.670199 0.038165 -0.954043 1.287773 0.266142 0.188886 0.918720 -0.222362\n6447 23.678077 0.036393 -0.954647 1.289226 0.259070 0.187079 0.922765 -0.215381\n6448 23.687452 0.035094 -0.955170 1.290424 0.252296 0.184792 0.926729 -0.208261\n6449 23.696032 0.034038 -0.955665 1.291464 0.246761 0.184376 0.930110 -0.200024\n6450 23.704347 0.032836 -0.956221 1.292043 0.242597 0.186277 0.932708 -0.191058\n6451 23.712039 0.031708 -0.956726 1.293168 0.236884 0.188031 0.935461 -0.182875\n6452 23.719413 0.030822 -0.957229 1.294031 0.234032 0.188448 0.938122 -0.172172\n6453 23.727672 0.029710 -0.957737 1.294509 0.236894 0.187534 0.939409 -0.161935\n6454 23.737221 0.028868 -0.958270 1.295259 0.237405 0.188031 0.940978 -0.151142\n6455 23.745816 0.027971 -0.958620 1.295871 0.237755 0.189663 0.942234 -0.140343\n6456 23.753613 0.027772 -0.959228 1.296525 0.243522 0.190563 0.942182 -0.129132\n6457 23.761664 0.027370 -0.958950 1.297006 0.248195 0.192098 0.942018 -0.118741\n6458 23.771016 0.027221 -0.959473 1.297412 0.252426 0.191791 0.942634 -0.104594\n6459 23.779411 0.027194 -0.959547 1.297271 0.257860 0.191145 0.942388 -0.094213\n6460 23.787219 0.026623 -0.959584 1.298211 0.263452 0.192191 0.941780 -0.081896\n6461 23.795185 0.026742 -0.959699 1.298512 0.270159 0.192207 0.940913 -0.068947\n6462 23.803533 0.027472 -0.959814 1.298898 0.281279 0.192014 0.938476 -0.057233\n6463 23.811877 0.027410 -0.959525 1.299137 0.289160 0.191518 0.936850 -0.044948\n6464 23.820570 0.028006 -0.959526 1.299108 0.298090 0.190820 0.934678 -0.033265\n6465 23.828296 0.028442 -0.959896 1.299499 0.307176 0.188601 0.932545 -0.020783\n6466 23.837366 0.029621 -0.959950 1.299296 0.317383 0.184660 0.930117 -0.007181\n6467 23.845525 0.030179 -0.960179 1.299543 0.327027 0.182706 0.927162 0.006508\n6468 23.853899 0.030515 -0.960034 1.299653 0.338025 0.178653 0.923794 0.020674\n6469 23.862037 0.031984 -0.961013 1.299629 0.349206 0.174159 0.920045 0.035231\n6470 23.869619 0.032820 -0.961320 1.299616 0.361265 0.170041 0.915493 0.049453\n6471 23.880830 0.034256 -0.961918 1.299179 0.372441 0.165234 0.910925 0.064821\n6472 23.886533 0.034560 -0.962344 1.299279 0.383749 0.160633 0.905947 0.078703\n6473 23.894665 0.035915 -0.963316 1.298966 0.395113 0.154990 0.900568 0.094022\n6474 23.904680 0.037121 -0.963567 1.298595 0.406653 0.149569 0.894845 0.107311\n6475 23.912173 0.037931 -0.964793 1.298719 0.415223 0.144098 0.889567 0.124481\n6476 23.919369 0.039195 -0.965667 1.298239 0.427780 0.139131 0.882078 0.139945\n6477 23.927895 0.040065 -0.966361 1.298045 0.436966 0.132426 0.876186 0.154347\n6478 23.936928 0.041388 -0.966526 1.297609 0.449777 0.126072 0.868372 0.166544\n6479 23.944968 0.042665 -0.967505 1.297011 0.459202 0.120112 0.861461 0.180534\n6480 23.953881 0.043526 -0.968406 1.296667 0.468449 0.113137 0.854750 0.192763\n6481 23.961691 0.044711 -0.968936 1.296368 0.478473 0.106559 0.847303 0.204418\n6482 23.970809 0.045451 -0.970270 1.296014 0.487469 0.100269 0.840260 0.215138\n6483 23.978854 0.046561 -0.971422 1.295350 0.492552 0.094797 0.834920 0.226528\n6484 23.988009 0.047573 -0.972377 1.294948 0.499859 0.089480 0.828376 0.236489\n6485 23.997019 0.049079 -0.973337 1.294693 0.512385 0.083594 0.818700 0.245365\n6486 24.003302 0.049925 -0.974912 1.294022 0.519855 0.078463 0.811454 0.255220\n6487 24.012680 0.050742 -0.975870 1.293303 0.525801 0.073749 0.805053 0.264543\n6488 24.020924 0.051513 -0.976512 1.292884 0.533005 0.069897 0.797557 0.273720\n6489 24.028425 0.052097 -0.977407 1.292418 0.537676 0.065342 0.791174 0.284041\n6490 24.037606 0.052617 -0.978164 1.292338 0.543963 0.064446 0.783832 0.292502\n6491 24.045573 0.053199 -0.979123 1.291692 0.548672 0.062040 0.777257 0.301633\n6492 24.052542 0.053810 -0.980300 1.291471 0.554301 0.059080 0.769501 0.311654\n6493 24.061546 0.054342 -0.980400 1.291222 0.557640 0.057900 0.763860 0.319692\n6494 24.070681 0.054527 -0.981596 1.290956 0.562153 0.057255 0.756802 0.328567\n6495 24.078000 0.055091 -0.982856 1.290225 0.565762 0.055910 0.750748 0.336400\n6496 24.087874 0.056110 -0.983686 1.289744 0.570542 0.052752 0.742937 0.346040\n6497 24.096413 0.056419 -0.985158 1.289261 0.574662 0.053195 0.736423 0.353008\n6498 24.103590 0.056954 -0.986366 1.288297 0.578804 0.050265 0.728581 0.362807\n6499 24.111906 0.057747 -0.987926 1.287575 0.583370 0.050923 0.721514 0.369466\n6500 24.121015 0.058340 -0.988973 1.287148 0.590787 0.046983 0.711936 0.376712\n6501 24.129501 0.059077 -0.990665 1.286008 0.595679 0.045098 0.703034 0.385845\n6502 24.137581 0.059907 -0.992069 1.285265 0.603421 0.044824 0.693496 0.391071\n6503 24.145399 0.060358 -0.993661 1.283844 0.609228 0.040192 0.684341 0.398627\n6504 24.154436 0.061014 -0.995130 1.282980 0.615997 0.037194 0.675126 0.404189\n6505 24.163808 0.061550 -0.996722 1.281744 0.622039 0.034439 0.666796 0.408980\n6506 24.170733 0.061943 -0.998420 1.280960 0.628651 0.031370 0.657729 0.413771\n6507 24.179561 0.062522 -1.000125 1.279897 0.635183 0.027700 0.648976 0.417858\n6508 24.187533 0.062939 -1.001999 1.278557 0.641274 0.023502 0.640692 0.421580\n6509 24.195669 0.063461 -1.003890 1.277310 -0.648087 -0.018964 -0.631645 -0.425028\n6510 24.204243 0.063868 -1.005755 1.276069 -0.654913 -0.014673 -0.622616 -0.428045\n6511 24.213061 0.064206 -1.007738 1.274535 -0.661645 -0.008795 -0.613711 -0.430705\n6512 24.221056 0.064614 -1.009600 1.273032 -0.668625 -0.003125 -0.604432 -0.433120\n6513 24.228418 0.065103 -1.011416 1.271636 -0.676059 0.002132 -0.594313 -0.435583\n6514 24.237706 0.065174 -1.013183 1.269845 -0.682799 0.008889 -0.585016 -0.437565\n6515 24.246057 0.065571 -1.015271 1.268352 -0.689075 0.014511 -0.575324 -0.440417\n6516 24.254109 0.065848 -1.017066 1.266797 -0.695428 0.020454 -0.565668 -0.442698\n6517 24.263309 0.066035 -1.018907 1.265152 -0.701544 0.026995 -0.555769 -0.445228\n6518 24.271060 0.066203 -1.020734 1.263265 -0.708249 0.034385 -0.545541 -0.446751\n6519 24.280213 0.066244 -1.022687 1.261320 -0.714235 0.041473 -0.534927 -0.449445\n6520 24.286856 0.066345 -1.024404 1.260303 -0.718716 0.046553 -0.526210 -0.452088\n6521 24.295864 0.065984 -1.026165 1.258027 -0.725688 0.052147 -0.514400 -0.453927\n6522 24.303206 0.066078 -1.027817 1.256416 -0.730972 0.057818 -0.504974 -0.455345\n6523 24.312491 0.065861 -1.029833 1.254319 -0.737106 0.063557 -0.493723 -0.457027\n6524 24.320208 0.065938 -1.031529 1.252528 -0.742456 0.068870 -0.484359 -0.457616\n6525 24.328935 0.065250 -1.033876 1.250849 -0.747567 0.074646 -0.476584 -0.456552\n6526 24.336064 0.066007 -1.034769 1.249017 -0.753372 0.078757 -0.467351 -0.455863\n6527 24.345524 0.066445 -1.036013 1.246750 -0.759783 0.083648 -0.457944 -0.453895\n6528 24.353830 0.066186 -1.037459 1.245159 -0.764348 0.087615 -0.451515 -0.451919\n6529 24.361454 0.066291 -1.038535 1.243473 -0.769440 0.091495 -0.444142 -0.449809\n6530 24.369233 0.066985 -1.039788 1.241964 -0.773822 0.095281 -0.438947 -0.446594\n6531 24.380410 0.066031 -1.040946 1.239627 -0.778479 0.099956 -0.431688 -0.444549\n6532 24.387184 0.067432 -1.042093 1.238398 -0.783143 0.104371 -0.427940 -0.438931\n6533 24.396069 0.067429 -1.042929 1.237017 -0.785988 0.108437 -0.425111 -0.435597\n6534 24.403637 0.068008 -1.044205 1.235134 -0.790241 0.112333 -0.420386 -0.431482\n6535 24.411335 0.067705 -1.045304 1.234175 -0.793053 0.113909 -0.417268 -0.428928\n6536 24.421371 0.068471 -1.046215 1.232819 -0.796208 0.119215 -0.415521 -0.423300\n6537 24.429742 0.068483 -1.047072 1.231446 -0.800460 0.123972 -0.410385 -0.418902\n6538 24.436393 0.069077 -1.047206 1.230512 -0.802366 0.126321 -0.410159 -0.414755\n6539 24.444047 0.068889 -1.048265 1.229540 -0.804270 0.129543 -0.408791 -0.411411\n6540 24.453942 0.069412 -1.048692 1.228486 -0.806959 0.132922 -0.406185 -0.407630\n6541 24.461655 0.069480 -1.049328 1.227553 -0.808870 0.136483 -0.404758 -0.404071\n6542 24.471172 0.069857 -1.049874 1.226637 -0.809549 0.138397 -0.405893 -0.400909\n6543 24.479000 0.070578 -1.050206 1.225838 -0.809421 0.142011 -0.407554 -0.398209\n6544 24.485999 0.070608 -1.050739 1.224593 -0.811609 0.144732 -0.405444 -0.394916\n6545 24.494222 0.071323 -1.051018 1.224200 -0.811315 0.147267 -0.407657 -0.392296\n6546 24.503306 0.071966 -1.051303 1.223561 -0.811265 0.149240 -0.409753 -0.389461\n6547 24.513058 0.072399 -1.051358 1.222813 -0.811792 0.151001 -0.411042 -0.386312\n6548 24.520911 0.073092 -1.051639 1.222391 -0.810858 0.153086 -0.414789 -0.383437\n6549 24.529105 0.073748 -1.051894 1.222078 -0.809598 0.153733 -0.419408 -0.380807\n6550 24.537442 0.074318 -1.051760 1.221646 -0.809513 0.155692 -0.421501 -0.377871\n6551 24.544199 0.074523 -1.051771 1.221442 -0.808506 0.156017 -0.426741 -0.373991\n6552 24.553315 0.075207 -1.051869 1.221574 -0.807264 0.155913 -0.432214 -0.370415\n6553 24.561197 0.075898 -1.051634 1.221432 -0.805727 0.154995 -0.437874 -0.367489\n6554 24.569611 0.076534 -1.051008 1.221907 -0.804739 0.156436 -0.442756 -0.363167\n6555 24.581475 0.077012 -1.050487 1.222070 -0.803905 0.152065 -0.449814 -0.358162\n6556 24.586980 0.077531 -1.050474 1.222770 -0.801842 0.150871 -0.456087 -0.355348\n6557 24.595696 0.078212 -1.050422 1.223206 -0.798602 0.149217 -0.463260 -0.354063\n6558 24.604210 0.078576 -1.049914 1.224021 -0.795908 0.145827 -0.471380 -0.350807\n6559 24.611074 0.078977 -1.049741 1.225052 -0.791660 0.143493 -0.479451 -0.350443\n6560 24.621979 0.079518 -1.049005 1.226043 -0.788048 0.141351 -0.487532 -0.348300\n6561 24.629302 0.080003 -1.048482 1.227262 -0.784650 0.138767 -0.494323 -0.347436\n6562 24.636839 0.080084 -1.047519 1.228630 -0.780188 0.134324 -0.503715 -0.345738\n6563 24.645559 0.081442 -1.046944 1.230339 -0.774641 0.131531 -0.512089 -0.346982\n6564 24.654135 0.081126 -1.046225 1.231179 -0.768639 0.129394 -0.521673 -0.346855\n6565 24.662200 0.081289 -1.045128 1.233305 -0.762615 0.125737 -0.530730 -0.347757\n6566 24.672608 0.081319 -1.044089 1.234758 -0.756304 0.123171 -0.540216 -0.347852\n6567 24.678742 0.081019 -1.042893 1.236774 -0.749155 0.119938 -0.550714 -0.347988\n6568 24.687548 0.081108 -1.042333 1.239314 -0.742487 0.117112 -0.559535 -0.349168\n6569 24.694321 0.081129 -1.040783 1.241000 -0.735825 0.114325 -0.568225 -0.350158\n6570 24.703661 0.080748 -1.039489 1.243076 -0.728521 0.111571 -0.578162 -0.350053\n6571 24.712702 0.080539 -1.038008 1.245413 -0.720935 0.108082 -0.588091 -0.350313\n6572 24.721665 0.080160 -1.036434 1.247961 -0.713213 0.103050 -0.598465 -0.350068\n6573 24.728071 0.079786 -1.034732 1.250642 -0.703967 0.096092 -0.610554 -0.349885\n6574 24.735987 0.079238 -1.033099 1.252967 -0.695435 0.090552 -0.621881 -0.348476\n6575 24.746194 0.078295 -1.031260 1.255726 -0.685313 0.082777 -0.634731 -0.347291\n6576 24.754339 0.077659 -1.029480 1.258453 -0.673955 0.075066 -0.648022 -0.346724\n6577 24.762711 0.076069 -1.027167 1.261034 0.663147 -0.065469 0.661430 0.344181\n6578 24.771015 0.074932 -1.025221 1.264187 0.649473 -0.059370 0.674756 0.345491\n6579 24.777850 0.074203 -1.023181 1.267197 0.636677 -0.049850 0.688622 0.343449\n6580 24.787274 0.072903 -1.021083 1.269984 0.622344 -0.042770 0.702256 0.343066\n6581 24.795272 0.071491 -1.019235 1.272955 0.608258 -0.033446 0.716398 0.340114\n6582 24.802496 0.070045 -1.016980 1.275674 0.593506 -0.026179 0.729122 0.339774\n6583 24.813303 0.068426 -1.014901 1.278779 0.579146 -0.020512 0.741136 0.338948\n6584 24.820718 0.066988 -1.012830 1.280995 0.564123 -0.013962 0.753426 0.337519\n6585 24.828240 0.065025 -1.010788 1.283802 0.549942 -0.007200 0.764499 0.336234\n6586 24.837386 0.063010 -1.008985 1.286686 0.535056 -0.002487 0.775487 0.335155\n6587 24.845575 0.060965 -1.006664 1.288774 0.522232 0.005485 0.785332 0.332411\n6588 24.854002 0.058868 -1.004663 1.291208 0.508663 0.011720 0.794928 0.330475\n6589 24.861695 0.056731 -1.002582 1.293667 0.495165 0.018238 0.804142 0.328381\n6590 24.870187 0.054561 -1.000514 1.296079 0.481674 0.024623 0.812990 0.326239\n6591 24.879437 0.052272 -0.998363 1.298441 0.468271 0.031139 0.821451 0.323993\n6592 24.887731 0.049949 -0.996198 1.300806 0.454508 0.037073 0.829748 0.321817\n6593 24.896404 0.047371 -0.994063 1.303098 0.440453 0.042842 0.837890 0.319540\n6594 24.903878 0.044735 -0.992038 1.305373 0.426109 0.047605 0.845765 0.317565\n6595 24.912008 0.041966 -0.990055 1.307541 0.411163 0.051972 0.853681 0.315393\n6596 24.919319 0.039009 -0.988179 1.309530 0.396128 0.055664 0.861310 0.313255\n6597 24.929620 0.035338 -0.986778 1.311563 0.380700 0.058376 0.868783 0.311250\n6598 24.936840 0.032673 -0.984452 1.313097 0.364480 0.061078 0.876781 0.307700\n6599 24.946024 0.029638 -0.983017 1.314831 0.350417 0.063569 0.882847 0.306184\n6600 24.953769 0.026788 -0.980866 1.316576 0.331206 0.065001 0.891239 0.302937\n6601 24.961403 0.023410 -0.979864 1.317874 0.316493 0.066512 0.897248 0.300590\n6602 24.970522 0.020492 -0.978070 1.319796 0.300108 0.067993 0.903289 0.298966\n6603 24.979102 0.018014 -0.977155 1.321027 0.288067 0.069189 0.908634 0.294305\n6604 24.986055 0.014887 -0.975477 1.322086 0.275250 0.071481 0.914148 0.288898\n6605 24.997019 0.011907 -0.974409 1.323174 0.257645 0.074013 0.919919 0.286166\n6606 25.004164 0.008871 -0.973551 1.324333 0.244068 0.075677 0.924845 0.281718\n6607 25.012455 0.006064 -0.971968 1.325054 0.231860 0.076301 0.929465 0.276612\n6608 25.020597 0.003206 -0.970829 1.326183 0.213727 0.078019 0.935134 0.271584\n6609 25.027821 0.000437 -0.970063 1.326993 0.201433 0.078846 0.939236 0.266541\n6610 25.037372 -0.002470 -0.969249 1.327818 0.186054 0.078332 0.943880 0.261415\n6611 25.054309 -0.008488 -0.967924 1.328967 0.159805 0.075719 0.951569 0.251488\n6612 25.054477 -0.008488 -0.967924 1.328967 0.159805 0.075719 0.951569 0.251488\n6613 25.061168 -0.011264 -0.967667 1.329400 0.148569 0.073091 0.954826 0.246764\n6614 25.070432 -0.013889 -0.967409 1.329705 0.137204 0.070191 0.957809 0.242590\n6615 25.080077 -0.017045 -0.967375 1.330008 0.125509 0.067190 0.960653 0.238492\n6616 25.086874 -0.020145 -0.966773 1.330096 0.114276 0.064018 0.963150 0.234916\n6617 25.094873 -0.022760 -0.967166 1.330207 0.104889 0.060333 0.965443 0.230820\n6618 25.104454 -0.025772 -0.967318 1.330180 0.093799 0.056397 0.967586 0.227592\n6619 25.111778 -0.027799 -0.967648 1.330047 0.083230 0.051023 0.969420 0.225155\n6620 25.119292 -0.031281 -0.967612 1.330029 0.070786 0.047222 0.970917 0.223786\n6621 25.127892 -0.033356 -0.968026 1.329931 0.064170 0.042134 0.971940 0.222349\n6622 25.136316 -0.036105 -0.968168 1.329693 0.051735 0.037873 0.973025 0.221612\n6623 25.146749 -0.038619 -0.968483 1.329472 0.043536 0.032977 0.973501 0.222066\n6624 25.153658 -0.040695 -0.968921 1.329285 0.039715 0.026823 0.973563 0.223334\n6625 25.163325 -0.043152 -0.969301 1.328984 0.033077 0.021100 0.973528 0.225174\n6626 25.170763 -0.045321 -0.969512 1.328568 0.027830 0.014349 0.973127 0.228129\n6627 25.177676 -0.047749 -0.969903 1.328182 0.022246 0.007474 0.972548 0.231515\n6628 25.187073 -0.050229 -0.970367 1.327793 0.016273 -0.000055 0.971623 0.235976\n6629 25.195926 -0.052626 -0.970840 1.327284 0.012296 -0.007648 0.970271 0.241590\n6630 25.203767 -0.054690 -0.970681 1.326895 0.008627 -0.016624 0.968660 0.247682\n6631 25.211140 -0.056526 -0.971507 1.326482 0.007101 -0.024858 0.966290 0.256155\n6632 25.219363 -0.058850 -0.971452 1.326255 0.004723 -0.032775 0.964035 0.263704\n6633 25.230348 -0.060903 -0.972094 1.325598 0.000711 -0.041299 0.961329 0.272286\n6634 25.237383 -0.063440 -0.972150 1.325171 -0.002720 -0.047160 0.958336 0.281711\n6635 25.246170 -0.065315 -0.972654 1.324635 -0.006099 -0.053119 0.955455 0.290252\n6636 25.253844 -0.067396 -0.972917 1.324111 -0.015153 -0.056741 0.952186 0.299821\n6637 25.261634 -0.069097 -0.973672 1.323777 -0.013588 -0.062508 0.948534 0.310146\n6638 25.270583 -0.070898 -0.974291 1.323343 -0.016453 -0.066804 0.944264 0.321918\n6639 25.279130 -0.072848 -0.975203 1.322982 -0.018163 -0.071279 0.939549 0.334421\n6640 25.287278 -0.074717 -0.975792 1.322441 -0.021294 -0.074391 0.934560 0.347291\n6641 25.295284 -0.076180 -0.976541 1.322022 -0.020570 -0.078967 0.929089 0.360742\n6642 25.302851 -0.077518 -0.977221 1.321713 -0.018310 -0.084324 0.923448 0.373897\n6643 25.312754 -0.078569 -0.977758 1.321610 -0.016759 -0.092125 0.916722 0.388397\n6644 25.320757 -0.078987 -0.978417 1.321762 -0.009132 -0.099070 0.910325 0.401759\n6645 25.327914 -0.080037 -0.978867 1.322122 -0.000206 -0.102967 0.902980 0.417164\n6646 25.336104 -0.080399 -0.979687 1.321806 0.008101 -0.104835 0.896799 0.429762\n6647 25.347501 -0.080169 -0.980292 1.322338 0.020757 -0.110913 0.888991 0.443804\n6648 25.353281 -0.080587 -0.980771 1.322824 0.032103 -0.112935 0.881475 0.457402\n6649 25.362609 -0.080279 -0.980829 1.323313 0.043453 -0.113483 0.873232 0.471910\n6650 25.371125 -0.079962 -0.981514 1.323763 0.056195 -0.114206 0.864207 0.486771\n6651 25.378022 -0.079508 -0.982135 1.324241 0.068454 -0.114599 0.855037 0.501092\n6652 25.389020 -0.079033 -0.983022 1.324610 0.082252 -0.114912 0.844588 0.516431\n6653 25.395122 -0.077806 -0.983602 1.324936 0.094485 -0.112280 0.834649 0.530873\n6654 25.402594 -0.077239 -0.984657 1.325266 0.106225 -0.115928 0.822826 0.546108\n6655 25.412438 -0.076683 -0.985923 1.325275 0.118604 -0.118229 0.811268 0.560177\n6656 25.420065 -0.075822 -0.987497 1.325166 0.130633 -0.121358 0.798753 0.574631\n6657 25.429183 -0.074842 -0.989195 1.325124 0.143432 -0.124810 0.785095 0.589471\n6658 25.437497 -0.074098 -0.990909 1.324786 0.154789 -0.130844 0.770931 0.603809\n6659 25.445794 -0.073617 -0.993089 1.324385 0.166815 -0.135884 0.756920 0.617075\n6660 25.455502 -0.073091 -0.995000 1.324064 0.178945 -0.139155 0.743970 0.628589\n6661 25.462374 -0.072344 -0.997177 1.323564 0.191735 -0.146266 0.729424 0.640144\n6662 25.469332 -0.071899 -0.999324 1.323163 0.203564 -0.148845 0.716031 0.650927\n6663 25.478873 -0.071356 -1.001517 1.322657 0.216096 -0.154864 0.703284 0.659327\n6664 25.486958 -0.070867 -1.003585 1.322042 0.227681 -0.158401 0.690641 0.667896\n6665 25.496039 -0.070273 -1.005761 1.321448 0.239499 -0.160978 0.678384 0.675664\n6666 25.503992 -0.070356 -1.007929 1.320658 0.250449 -0.163554 0.666462 0.682901\n6667 25.511090 -0.070442 -1.010040 1.319886 0.260900 -0.166442 0.654925 0.689421\n6668 25.519269 -0.069907 -1.012437 1.319110 0.270871 -0.169430 0.643511 0.695569\n6669 25.529494 -0.069817 -1.014666 1.318380 0.280658 -0.173839 0.632215 0.700939\n6670 25.537276 -0.069729 -1.016890 1.317559 0.290317 -0.177747 0.620635 0.706353\n6671 25.545538 -0.069791 -1.019038 1.316775 0.300053 -0.182647 0.608903 0.711228\n6672 25.553490 -0.069771 -1.021267 1.315962 0.310248 -0.187445 0.596743 0.715897\n6673 25.562701 -0.069915 -1.023410 1.314812 0.321102 -0.192157 0.583088 0.721095\n6674 25.571774 -0.069906 -1.025573 1.314449 0.331157 -0.193752 0.569720 0.726783\n6675 25.578723 -0.070306 -1.027356 1.313711 0.341615 -0.198980 0.554457 0.732314\n6676 25.585966 -0.070061 -1.029301 1.312968 0.352907 -0.204241 0.539305 0.736812\n6677 25.596099 -0.069961 -1.030980 1.312208 0.363590 -0.210644 0.523772 0.741009\n6678 25.604284 -0.070485 -1.032263 1.311614 0.373254 -0.216462 0.506924 0.746227\n6679 25.612498 -0.070591 -1.033498 1.311051 0.382065 -0.221408 0.490051 0.751569\n6680 25.620912 -0.070490 -1.034897 1.310658 0.390718 -0.224719 0.473299 0.756855\n6681 25.627963 -0.070828 -1.035906 1.310180 0.397777 -0.230479 0.456220 0.761917\n6682 25.637337 -0.071041 -1.037003 1.309780 0.404620 -0.232652 0.440022 0.767161\n6683 25.645895 -0.071341 -1.037738 1.309547 0.410502 -0.235095 0.423925 0.772338\n6684 25.655495 -0.072098 -1.038784 1.308917 0.415455 -0.237576 0.406701 0.778171\n6685 25.661891 -0.071857 -1.039662 1.308815 0.421178 -0.237781 0.392272 0.782427\n6686 25.669326 -0.072471 -1.040427 1.308449 0.425721 -0.240964 0.375836 0.787048\n6687 25.678078 -0.072935 -1.041209 1.308183 0.430814 -0.240432 0.359611 0.792004\n6688 25.686772 -0.073047 -1.041954 1.307944 0.435448 -0.243401 0.343324 0.795783\n6689 25.696507 -0.073716 -1.042475 1.307797 0.439538 -0.246779 0.326099 0.799729\n6690 25.704355 -0.074329 -1.043049 1.307698 0.443850 -0.248299 0.309091 0.803621\n6691 25.713093 -0.074514 -1.043588 1.307570 0.448101 -0.249018 0.292533 0.807230\n6692 25.722031 -0.075157 -1.043703 1.307831 0.451588 -0.250554 0.276056 0.810607\n6693 25.728430 -0.075317 -1.043846 1.307958 0.454929 -0.251140 0.259604 0.813986\n6694 25.736069 -0.075920 -1.044412 1.307527 0.457200 -0.252656 0.242937 0.817383\n6695 25.744628 -0.075907 -1.044941 1.307710 0.460428 -0.252032 0.228202 0.820006\n6696 25.753205 -0.076392 -1.045185 1.307739 0.463234 -0.251941 0.213093 0.822515\n6697 25.760865 -0.076693 -1.045612 1.307529 0.465767 -0.251217 0.198784 0.824886\n6698 25.770593 -0.076768 -1.045933 1.307559 0.469947 -0.250884 0.185949 0.825609\n6699 25.778662 -0.077388 -1.046387 1.307551 0.473590 -0.252380 0.173006 0.825885\n6700 25.786161 -0.077518 -1.046803 1.307632 0.478024 -0.251646 0.160978 0.825987\n6701 25.796341 -0.077782 -1.047258 1.307393 0.482728 -0.253261 0.148667 0.825064\n6702 25.803299 -0.078523 -1.048087 1.306848 0.487042 -0.255020 0.136589 0.824074\n6703 25.811630 -0.078430 -1.048466 1.306858 0.492837 -0.258210 0.126249 0.821280\n6704 25.820909 -0.079213 -1.049642 1.306067 0.497597 -0.261367 0.114946 0.819068\n6705 25.829566 -0.079650 -1.050410 1.305438 0.501617 -0.264312 0.104405 0.817080\n6706 25.837135 -0.080034 -1.050962 1.304813 0.507817 -0.270535 0.093219 0.812553\n6707 25.845955 -0.080662 -1.051747 1.304350 0.513443 -0.274149 0.084125 0.808790\n6708 25.853101 -0.081742 -1.053098 1.303185 0.518308 -0.277923 0.075027 0.805286\n6709 25.862642 -0.082523 -1.053847 1.302683 0.524014 -0.284003 0.065783 0.800265\n6710 25.870031 -0.083327 -1.054624 1.302112 0.527851 -0.286792 0.057563 0.797377\n6711 25.877565 -0.084518 -1.055557 1.301037 0.531606 -0.291016 0.049192 0.793905\n6712 25.887394 -0.085260 -1.055936 1.300666 0.535199 -0.296502 0.042024 0.789863\n6713 25.896153 -0.086042 -1.056524 1.299881 0.537438 -0.300497 0.036240 0.787114\n6714 25.902653 -0.086984 -1.056871 1.299158 0.538470 -0.302747 0.028999 0.785846\n6715 25.910885 -0.088170 -1.057459 1.298859 0.542210 -0.307622 0.026516 0.781457\n6716 25.920188 -0.089337 -1.057690 1.298202 0.543663 -0.312455 0.021369 0.778682\n6717 25.927420 -0.090915 -1.058082 1.297723 0.545824 -0.316553 0.017293 0.775611\n6718 25.937169 -0.091910 -1.058547 1.296539 0.547021 -0.317884 0.014972 0.774270\n6719 25.945762 -0.092936 -1.059038 1.296523 0.549548 -0.320640 0.012793 0.771378\n6720 25.953888 -0.093971 -1.059170 1.296126 0.551306 -0.323920 0.009678 0.768794\n6721 25.962150 -0.095369 -1.060058 1.295516 0.555399 -0.329010 0.005303 0.763712\n6722 25.969473 -0.096356 -1.060673 1.295066 0.556366 -0.330362 0.005130 0.762425\n6723 25.981065 -0.097517 -1.061444 1.293768 0.558266 -0.333663 0.002853 0.759605\n6724 25.986946 -0.098451 -1.062103 1.293196 0.560127 -0.335738 0.000438 0.757323\n6725 25.996018 -0.100161 -1.062803 1.291546 0.561461 -0.340781 -0.002652 0.754071\n6726 26.003958 -0.100959 -1.063616 1.291345 0.565158 -0.342408 -0.003936 0.750558\n6727 26.010742 -0.102795 -1.064444 1.290073 0.566706 -0.348384 -0.008005 0.746598\n6728 26.020739 -0.104149 -1.064998 1.289230 0.567808 -0.352611 -0.010554 0.743739\n6729 26.029052 -0.105579 -1.065696 1.287806 0.569387 -0.357124 -0.013537 0.740322\n6730 26.037386 -0.106621 -1.066472 1.287292 0.571718 -0.360647 -0.015202 0.736777\n6731 26.044245 -0.108048 -1.067388 1.285936 0.574106 -0.365240 -0.016311 0.732623\n6732 26.054231 -0.109180 -1.068182 1.284294 0.575391 -0.371633 -0.018066 0.728346\n6733 26.063350 -0.110079 -1.069072 1.284178 0.578522 -0.372052 -0.017091 0.725670\n6734 26.070515 -0.110592 -1.069437 1.283152 0.580104 -0.372153 -0.015149 0.724398\n6735 26.077612 -0.111849 -1.070108 1.282355 0.580974 -0.376118 -0.014985 0.721651\n6736 26.085908 -0.112276 -1.070815 1.281903 0.582521 -0.379248 -0.013849 0.718782\n6737 26.096415 -0.113089 -1.071227 1.281420 0.583715 -0.382228 -0.012286 0.716259\n6738 26.103589 -0.112538 -1.072101 1.281087 0.584131 -0.380986 -0.008360 0.716639\n6739 26.112194 -0.113030 -1.072498 1.279938 0.585276 -0.381434 -0.005620 0.715492\n6740 26.120418 -0.113159 -1.073028 1.280026 0.585868 -0.381832 -0.001654 0.714815\n6741 26.127523 -0.112957 -1.073712 1.279817 0.586952 -0.381921 0.001820 0.713877\n6742 26.138175 -0.113230 -1.073723 1.279423 0.586074 -0.381299 0.006675 0.714901\n6743 26.145777 -0.112198 -1.074952 1.279970 0.589032 -0.379426 0.011430 0.713406\n6744 26.153701 -0.111683 -1.073947 1.279603 0.586023 -0.377285 0.016767 0.716905\n6745 26.161108 -0.109422 -1.074206 1.279732 0.586850 -0.376199 0.024711 0.716569\n6746 26.170014 -0.109514 -1.074970 1.280054 0.586635 -0.370105 0.028079 0.719787\n6747 26.179244 -0.107476 -1.074474 1.280605 0.584641 -0.366055 0.035855 0.723127\n6748 26.187849 -0.106520 -1.075020 1.281522 0.585690 -0.360702 0.043640 0.724540\n6749 26.195281 -0.105399 -1.074806 1.281550 0.585602 -0.356674 0.051615 0.726079\n6750 26.202772 -0.103417 -1.074900 1.281914 0.585685 -0.348557 0.062474 0.729094\n6751 26.213797 -0.102241 -1.074589 1.282606 0.585225 -0.342023 0.071484 0.731726\n6752 26.220045 -0.100319 -1.074550 1.282962 0.586094 -0.335669 0.082707 0.732789\n6753 26.229319 -0.098391 -1.074030 1.284040 0.585633 -0.327551 0.095145 0.735318\n6754 26.237425 -0.096530 -1.073441 1.284928 0.585746 -0.320166 0.107764 0.736737\n6755 26.244699 -0.094226 -1.072875 1.285920 0.583569 -0.310469 0.122521 0.740301\n6756 26.254054 -0.091957 -1.072281 1.286709 0.582488 -0.299945 0.138945 0.742587\n6757 26.262871 -0.089936 -1.071099 1.288044 0.579583 -0.293301 0.153806 0.744582\n6758 26.270030 -0.087777 -1.070032 1.289598 0.576481 -0.281622 0.171461 0.747637\n6759 26.280230 -0.086124 -1.069223 1.290465 0.572228 -0.273431 0.188922 0.749732\n6760 26.286776 -0.084287 -1.067885 1.291505 0.565980 -0.263526 0.208266 0.752892\n6761 26.294940 -0.082511 -1.066336 1.293156 0.560278 -0.253675 0.227432 0.754991\n6762 26.303793 -0.080601 -1.064457 1.294683 0.553459 -0.244350 0.247323 0.756840\n6763 26.312245 -0.078977 -1.062582 1.296147 0.545839 -0.232634 0.268317 0.758912\n6764 26.320643 -0.077167 -1.060672 1.297615 0.537803 -0.221704 0.289702 0.760058\n6765 26.328642 -0.075607 -1.058550 1.299293 0.529376 -0.211594 0.310007 0.760844\n6766 26.336116 -0.073653 -1.056501 1.300617 0.520040 -0.200062 0.332068 0.761095\n6767 26.346777 -0.072273 -1.054657 1.301859 0.510164 -0.189308 0.352959 0.761128\n6768 26.354322 -0.070238 -1.052228 1.303907 0.501167 -0.176513 0.373960 0.760151\n6769 26.362967 -0.068656 -1.049876 1.305320 0.492357 -0.166213 0.396229 0.756942\n6770 26.370198 -0.068200 -1.047291 1.306714 0.481741 -0.157885 0.416128 0.754875\n6771 26.377785 -0.066091 -1.045330 1.308298 0.473679 -0.145325 0.436421 0.751029\n6772 26.386082 -0.064882 -1.043279 1.308560 0.464233 -0.138141 0.457594 0.745662\n6773 26.396957 -0.064543 -1.040478 1.310608 0.457243 -0.131414 0.476216 0.739512\n6774 26.404283 -0.063039 -1.038323 1.312113 0.449679 -0.121752 0.496143 0.732672\n6775 26.412821 -0.061977 -1.036167 1.313432 0.442364 -0.114963 0.514458 0.725555\n6776 26.420948 -0.061531 -1.033997 1.314855 0.435279 -0.111058 0.529803 0.719380\n6777 26.427762 -0.060783 -1.032104 1.315686 0.429643 -0.106966 0.546978 0.710479\n6778 26.437130 -0.059913 -1.029918 1.316794 0.425308 -0.100130 0.563286 0.701282\n6779 26.445974 -0.059106 -1.027872 1.317976 0.421105 -0.095127 0.579683 0.691078\n6780 26.453779 -0.058346 -1.025961 1.319021 0.417480 -0.090201 0.594672 0.681131\n6781 26.461951 -0.057529 -1.024340 1.320082 0.414336 -0.085404 0.609271 0.670687\n6782 26.469508 -0.056494 -1.022423 1.321097 0.410579 -0.077763 0.624889 0.659463\n6783 26.480083 -0.055639 -1.020761 1.322104 0.407525 -0.073240 0.638632 0.648621\n6784 26.487714 -0.054958 -1.019392 1.322853 0.405219 -0.069465 0.652922 0.636133\n6785 26.494759 -0.054587 -1.018006 1.323384 0.400472 -0.063200 0.667685 0.624360\n6786 26.502740 -0.053511 -1.015306 1.325246 0.394386 -0.052304 0.682256 0.613394\n6787 26.514003 -0.052969 -1.013350 1.326288 0.389394 -0.045048 0.696390 0.601152\n6788 26.520214 -0.052608 -1.010941 1.327687 0.383467 -0.037986 0.711835 0.587198\n6789 26.528483 -0.052411 -1.009266 1.328406 0.380110 -0.029182 0.724352 0.574437\n6790 26.537439 -0.052306 -1.006832 1.329589 0.370934 -0.019172 0.739327 0.561637\n6791 26.545779 -0.052327 -1.004782 1.330544 0.362276 -0.011094 0.753201 0.548927\n6792 26.554149 -0.052417 -1.002068 1.331810 0.351442 -0.001593 0.767484 0.536148\n6793 26.560889 -0.052727 -0.999621 1.332882 0.338561 0.007892 0.781789 0.523565\n6794 26.570730 -0.052749 -0.997020 1.333981 0.321586 0.015113 0.797814 0.509752\n6795 26.579383 -0.052875 -0.995691 1.335378 0.306344 0.022009 0.809644 0.500145\n6796 26.587339 -0.053309 -0.992580 1.336381 0.295242 0.032594 0.822257 0.485452\n6797 26.594453 -0.053579 -0.990091 1.337388 0.283956 0.041196 0.834417 0.470553\n6798 26.603838 -0.053793 -0.987500 1.338369 0.271545 0.049498 0.845812 0.456525\n6799 26.613367 -0.054357 -0.985082 1.339388 0.258213 0.058778 0.857455 0.441182\n6800 26.620633 -0.055031 -0.982998 1.340231 0.247678 0.066221 0.867748 0.425774\n6801 26.627547 -0.056223 -0.980284 1.340982 0.235854 0.074748 0.877260 0.411340\n6802 26.637380 -0.057598 -0.978032 1.341781 0.228446 0.082610 0.885566 0.395931\n6803 26.645738 -0.058273 -0.975825 1.342442 0.217355 0.091245 0.894604 0.379625\n6804 26.653962 -0.059432 -0.973879 1.343087 0.208390 0.099448 0.902956 0.362427\n6805 26.662553 -0.060262 -0.972172 1.343809 0.199287 0.108238 0.911149 0.344059\n6806 26.669629 -0.061244 -0.970323 1.344478 0.191209 0.117142 0.918578 0.325471\n6807 26.679524 -0.062496 -0.968062 1.345601 0.177001 0.125473 0.926846 0.306405\n6808 26.686819 -0.063427 -0.966669 1.346095 0.171174 0.135346 0.932917 0.286437\n6809 26.695919 -0.064356 -0.964648 1.346777 0.161115 0.142935 0.939307 0.267047\n6810 26.704083 -0.065026 -0.962809 1.347303 0.152976 0.148881 0.945528 0.245783\n6811 26.711149 -0.065790 -0.961206 1.347866 0.142872 0.152723 0.951788 0.224417\n6812 26.719354 -0.067403 -0.959689 1.348285 0.133711 0.156502 0.957222 0.203358\n6813 26.730583 -0.067261 -0.959040 1.348944 0.126067 0.154870 0.962639 0.182887\n6814 26.736581 -0.068247 -0.958052 1.349273 0.118089 0.154623 0.967497 0.161543\n6815 26.745669 -0.068891 -0.957545 1.349760 0.107048 0.152484 0.972176 0.142001\n6816 26.753829 -0.070277 -0.956778 1.350433 0.095543 0.149665 0.976727 0.120322\n6817 26.760953 -0.071498 -0.956304 1.350841 0.086497 0.148223 0.980085 0.099908\n6818 26.770719 -0.072104 -0.955934 1.350962 0.080417 0.148977 0.982233 0.080982\n6819 26.779224 -0.073419 -0.955105 1.351292 0.071353 0.149818 0.984371 0.058964\n6820 26.786140 -0.074593 -0.954560 1.351274 0.062127 0.150527 0.985871 0.039241\n6821 26.796931 -0.075846 -0.953785 1.351504 0.048568 0.150250 0.987253 0.019924\n6822 26.803284 -0.076724 -0.953275 1.351748 0.041326 0.150260 0.987782 0.000867\n6823 26.811354 -0.077428 -0.952745 1.351988 0.033015 0.151650 0.987720 -0.017923\n6824 26.820978 -0.077979 -0.952266 1.352275 0.026548 0.153320 0.987150 -0.036381\n6825 26.830081 -0.078323 -0.951828 1.352623 0.022707 0.154482 0.986265 -0.053864\n6826 26.837352 -0.078983 -0.951424 1.352925 0.016170 0.156391 0.984979 -0.071386\n6827 26.844312 -0.079155 -0.951082 1.353043 0.015479 0.157126 0.983556 -0.087688\n6828 26.853177 -0.080055 -0.950476 1.353529 0.008092 0.159138 0.981822 -0.103125\n6829 26.862761 -0.080624 -0.950033 1.353832 0.004606 0.159810 0.980124 -0.117460\n6830 26.870723 -0.081215 -0.949547 1.354152 0.001600 0.161393 0.978132 -0.131175\n6831 26.878039 -0.081827 -0.949094 1.354491 -0.001242 0.162260 0.976300 -0.143208\n6832 26.887788 -0.082218 -0.948503 1.354836 -0.003973 0.162783 0.974573 -0.153929\n6833 26.896487 -0.083053 -0.947908 1.355079 -0.010517 0.163687 0.972616 -0.164663\n6834 26.904167 -0.083753 -0.947334 1.355292 -0.016603 0.164192 0.970729 -0.174500\n6835 26.911043 -0.083834 -0.946643 1.355573 -0.018118 0.162873 0.969439 -0.182569\n6836 26.920069 -0.084689 -0.946101 1.356016 -0.025202 0.163533 0.967541 -0.191015\n6837 26.927675 -0.085622 -0.945758 1.356403 -0.034603 0.163721 0.965711 -0.198496\n6838 26.939078 -0.085163 -0.946004 1.357019 -0.035746 0.161078 0.965167 -0.203049\n6839 26.944692 -0.086728 -0.944799 1.357147 -0.043399 0.161135 0.963325 -0.210138\n6840 26.953545 -0.087685 -0.944391 1.357253 -0.054335 0.158272 0.962309 -0.214380\n6841 26.960968 -0.088495 -0.944071 1.357528 -0.061473 0.155909 0.961652 -0.217115\n6842 26.970404 -0.089241 -0.943701 1.357589 -0.069710 0.151820 0.961393 -0.218665\n6843 26.978673 -0.089949 -0.943385 1.357681 -0.075618 0.148127 0.961402 -0.219196\n6844 26.986539 -0.090906 -0.943036 1.357617 -0.083575 0.143819 0.961475 -0.218853\n6845 26.996476 -0.091948 -0.942601 1.357443 -0.091892 0.138926 0.961861 -0.216975\n6846 27.002646 -0.093034 -0.942143 1.357399 -0.098848 0.135939 0.962016 -0.215115\n6847 27.010934 -0.094333 -0.941540 1.357326 -0.105757 0.133706 0.962321 -0.211842\n6848 27.020597 -0.095382 -0.940968 1.357387 -0.111151 0.132304 0.962707 -0.208172\n6849 27.029151 -0.096532 -0.940242 1.357399 -0.117567 0.131859 0.963077 -0.203160\n6850 27.038392 -0.097685 -0.939633 1.357522 -0.121330 0.131597 0.963821 -0.197511\n6851 27.044268 -0.098730 -0.938771 1.357496 -0.124341 0.131034 0.965005 -0.190094\n6852 27.052759 -0.098983 -0.938074 1.357666 -0.119527 0.130206 0.967184 -0.182524\n6853 27.063200 -0.100187 -0.937441 1.357738 -0.124931 0.130555 0.968143 -0.173343\n6854 27.070340 -0.100764 -0.936905 1.357795 -0.123831 0.129360 0.970234 -0.163030\n6855 27.079301 -0.101219 -0.936059 1.357543 -0.116379 0.129296 0.972971 -0.151872\n6856 27.087457 -0.101402 -0.935097 1.357508 -0.110524 0.125951 0.975955 -0.139404\n6857 27.094881 -0.101941 -0.934464 1.357478 -0.107515 0.122324 0.978803 -0.124184\n6858 27.104616 -0.102410 -0.933851 1.357570 -0.107561 0.117456 0.981155 -0.109406\n6859 27.111995 -0.102712 -0.932649 1.357695 -0.107048 0.112382 0.983562 -0.092289\n6860 27.120540 -0.103130 -0.931703 1.357537 -0.103692 0.109063 0.985690 -0.075953\n6861 27.127721 -0.103803 -0.931263 1.357450 -0.101346 0.106528 0.987303 -0.060113\n6862 27.137356 -0.103702 -0.930301 1.357365 -0.095034 0.101161 0.989368 -0.043424\n6863 27.145057 -0.103996 -0.929624 1.357338 -0.089913 0.096658 0.990886 -0.026801\n6864 27.154716 -0.103925 -0.928432 1.357336 -0.085927 0.092709 0.991932 -0.009654\n6865 27.162924 -0.104182 -0.927423 1.357701 -0.081595 0.090191 0.992558 0.006070\n6866 27.169345 -0.103988 -0.926412 1.357928 -0.074935 0.086429 0.993185 0.022309\n6867 27.178466 -0.103607 -0.925313 1.358255 -0.067459 0.082883 0.993523 0.038622\n6868 27.187297 -0.102882 -0.924571 1.358618 -0.058948 0.079765 0.993574 0.054528\n6869 27.194417 -0.102400 -0.923392 1.359004 -0.049399 0.077558 0.993274 0.070363\n6870 27.202629 -0.101648 -0.922283 1.359340 -0.040832 0.075540 0.992561 0.086314\n6871 27.213453 -0.101026 -0.921696 1.359524 -0.030957 0.075510 0.991376 0.102537\n6872 27.220964 -0.100098 -0.920265 1.360048 -0.024229 0.070204 0.990190 0.118353\n6873 27.229498 -0.098770 -0.919211 1.360542 -0.014393 0.067372 0.988582 0.134014\n6874 27.236649 -0.097430 -0.918328 1.361100 -0.004120 0.063076 0.986691 0.149818\n6875 27.244180 -0.095381 -0.917568 1.361628 0.008455 0.057875 0.984402 0.165928\n6876 27.253984 -0.094063 -0.916734 1.361993 0.020272 0.053126 0.981710 0.181690\n6877 27.263214 -0.092200 -0.916098 1.362447 0.031131 0.047338 0.978668 0.197484\n6878 27.271139 -0.090569 -0.915667 1.362733 0.044458 0.041685 0.975201 0.212765\n6879 27.278608 -0.088115 -0.915266 1.363226 0.060391 0.034462 0.970836 0.229439\n6880 27.286244 -0.085778 -0.915053 1.363713 0.072728 0.027239 0.966152 0.246007\n6881 27.298646 -0.083767 -0.914764 1.364118 0.086893 0.019771 0.960835 0.262402\n6882 27.305556 -0.081390 -0.914633 1.364422 0.101499 0.011454 0.954742 0.279346\n6883 27.313919 -0.079534 -0.914854 1.364783 0.115019 0.002626 0.947928 0.296979\n6884 27.320511 -0.076154 -0.914657 1.364930 0.127276 -0.007851 0.940514 0.314917\n6885 27.330058 -0.073941 -0.915016 1.365111 0.141667 -0.015955 0.931617 0.334315\n6886 27.337474 -0.071318 -0.915672 1.365173 0.155782 -0.027402 0.922645 0.351720\n6887 27.345039 -0.068997 -0.916071 1.365222 0.166710 -0.036901 0.913102 0.370257\n6888 27.352725 -0.067020 -0.916098 1.365181 0.174848 -0.044513 0.903561 0.388618\n6889 27.362717 -0.065006 -0.916668 1.365093 0.183532 -0.053544 0.892893 0.407665\n6890 27.371054 -0.062984 -0.917068 1.365212 0.188184 -0.064228 0.881974 0.427298\n6891 27.377704 -0.061099 -0.917138 1.364886 0.197802 -0.070379 0.870118 0.445888\n6892 27.386216 -0.059166 -0.917469 1.364447 0.206362 -0.080313 0.857280 0.464796\n6893 27.395909 -0.057228 -0.917879 1.364307 0.213109 -0.087917 0.844291 0.483764\n6894 27.404357 -0.055009 -0.918095 1.364034 0.220464 -0.095425 0.830896 0.501897\n6895 27.412434 -0.053448 -0.918741 1.363841 0.227419 -0.101530 0.817153 0.519840\n6896 27.420664 -0.051203 -0.919033 1.363578 0.233621 -0.107411 0.803300 0.537210\n6897 27.428998 -0.049290 -0.919552 1.363241 0.240061 -0.113145 0.789751 0.553048\n6898 27.437903 -0.047216 -0.920544 1.362785 0.245749 -0.121067 0.774331 0.570405\n6899 27.444840 -0.045275 -0.920869 1.362427 0.250228 -0.125743 0.759962 0.586542\n6900 27.453861 -0.043141 -0.921451 1.361923 0.253893 -0.129791 0.745043 0.602996\n6901 27.461161 -0.041370 -0.922204 1.361529 0.258740 -0.136654 0.731300 0.616101\n6902 27.469945 -0.039931 -0.923231 1.360898 0.262648 -0.142970 0.715607 0.631255\n6903 27.480626 -0.037628 -0.923811 1.360831 0.266550 -0.146631 0.701809 0.644139\n6904 27.486981 -0.036266 -0.924810 1.360426 0.270449 -0.148413 0.686415 0.658533\n6905 27.494298 -0.034625 -0.926122 1.359973 0.275659 -0.152798 0.670565 0.671571\n6906 27.504155 -0.033124 -0.927457 1.359470 0.281201 -0.157994 0.654493 0.683815\n6907 27.512366 -0.031180 -0.929034 1.358981 0.287225 -0.161971 0.638173 0.695703\n6908 27.519718 -0.029527 -0.930758 1.357991 0.291591 -0.165223 0.619996 0.709423\n6909 27.528159 -0.027575 -0.932746 1.357985 0.298884 -0.168212 0.604141 0.719296\n6910 27.537695 -0.026062 -0.935113 1.357251 0.306467 -0.173989 0.585956 0.729699\n6911 27.544981 -0.024656 -0.937831 1.356341 0.314088 -0.180272 0.566039 0.740574\n6912 27.553938 -0.023289 -0.940636 1.355347 0.321837 -0.186566 0.546253 0.750481\n6913 27.562285 -0.021892 -0.943531 1.354392 0.330341 -0.192303 0.526647 0.759301\n6914 27.571436 -0.020669 -0.946373 1.353194 0.338637 -0.199611 0.506232 0.767600\n6915 27.578507 -0.019405 -0.949303 1.351997 0.346823 -0.205724 0.485648 0.775589\n6916 27.586511 -0.019107 -0.951852 1.350722 0.354811 -0.215739 0.464361 0.782262\n6917 27.595175 -0.017908 -0.954565 1.349538 0.362261 -0.221377 0.446298 0.787768\n6918 27.604216 -0.017200 -0.957047 1.348288 0.368911 -0.227826 0.427831 0.793070\n6919 27.611602 -0.016703 -0.959439 1.346958 0.375286 -0.235323 0.409651 0.797477\n6920 27.619873 -0.016113 -0.961811 1.345658 0.381459 -0.240742 0.392388 0.801601\n6921 27.627963 -0.015816 -0.963912 1.344546 0.387565 -0.247023 0.376127 0.804551\n6922 27.637841 -0.015346 -0.965958 1.342912 0.392716 -0.252728 0.359366 0.807935\n6923 27.645495 -0.014300 -0.968521 1.341873 0.399934 -0.255792 0.343442 0.810352\n6924 27.654577 -0.013593 -0.970675 1.340508 0.406127 -0.259419 0.327391 0.812759\n6925 27.661537 -0.013273 -0.972726 1.339031 0.412144 -0.264511 0.311581 0.814303\n6926 27.670431 -0.012973 -0.974910 1.337613 0.418066 -0.268335 0.295888 0.815885\n6927 27.678813 -0.012638 -0.977068 1.335967 0.424614 -0.274254 0.279681 0.816252\n6928 27.687892 -0.012207 -0.979419 1.334349 0.431701 -0.276683 0.264534 0.816763\n6929 27.696120 -0.012254 -0.981316 1.332576 0.438618 -0.282520 0.247376 0.816457\n6930 27.703955 -0.011823 -0.983660 1.331164 0.447351 -0.286147 0.231981 0.814973\n6931 27.711102 -0.011621 -0.985608 1.329027 0.453784 -0.292659 0.215894 0.813524\n6932 27.720178 -0.012415 -0.987781 1.326837 0.459596 -0.296582 0.198707 0.813220\n6933 27.728167 -0.012055 -0.990024 1.324796 0.466461 -0.302100 0.182988 0.810966\n6934 27.737126 -0.012050 -0.991650 1.323000 0.470806 -0.308313 0.168431 0.809268\n6935 27.745439 -0.011867 -0.993434 1.320584 0.475533 -0.315418 0.154728 0.806498\n6936 27.753952 -0.012168 -0.994988 1.318950 0.479104 -0.321985 0.142383 0.804060\n6937 27.761644 -0.011686 -0.996923 1.317008 0.483501 -0.326030 0.131094 0.801714\n6938 27.771287 -0.011369 -0.998077 1.315644 0.488793 -0.330985 0.121086 0.798040\n6939 27.780280 -0.011721 -1.000093 1.312809 0.491428 -0.335347 0.110186 0.796179\n6940 27.789190 -0.011493 -1.001798 1.311170 0.495976 -0.337371 0.100976 0.793721\n6941 27.796150 -0.011243 -1.003622 1.309085 0.500956 -0.339846 0.091237 0.790711\n6942 27.803730 -0.011172 -1.005167 1.306624 0.506337 -0.342238 0.081295 0.787329\n6943 27.812207 -0.011117 -1.007334 1.304588 0.513151 -0.343639 0.071659 0.783233\n6944 27.820819 -0.010926 -1.008935 1.302959 0.519933 -0.344695 0.062782 0.779047\n6945 27.827716 -0.011218 -1.010769 1.300720 0.526552 -0.343160 0.055229 0.775844\n6946 27.836351 -0.011491 -1.012396 1.299876 0.533854 -0.344090 0.047001 0.770969\n6947 27.847976 -0.011634 -1.013827 1.298012 0.539477 -0.341526 0.041275 0.768519\n6948 27.853990 -0.011482 -1.015470 1.296656 0.546291 -0.340082 0.037297 0.764539\n6949 27.862261 -0.011501 -1.017239 1.294804 0.552077 -0.339338 0.033013 0.760901\n6950 27.869978 -0.012207 -1.018750 1.293259 0.557766 -0.335975 0.029949 0.758367\n6951 27.877721 -0.011544 -1.020579 1.291889 0.564206 -0.333305 0.028061 0.754846\n6952 27.887203 -0.010925 -1.021812 1.290832 0.570498 -0.327943 0.028000 0.752464\n6953 27.895053 -0.010626 -1.023117 1.289284 0.576077 -0.326363 0.025425 0.748983\n6954 27.902945 -0.010726 -1.024061 1.288016 0.581334 -0.323665 0.023768 0.746141\n6955 27.911733 -0.009662 -1.025532 1.286734 0.586874 -0.317635 0.021637 0.744458\n6956 27.920040 -0.009040 -1.026644 1.285386 0.592640 -0.312300 0.022498 0.742119\n6957 27.927757 -0.008262 -1.027526 1.284821 0.599051 -0.307703 0.022652 0.738880\n6958 27.935917 -0.007729 -1.028436 1.284033 0.605033 -0.303842 0.020211 0.735668\n6959 27.947170 -0.007005 -1.029172 1.282951 0.610346 -0.297295 0.020701 0.733938\n6960 27.953592 -0.006156 -1.030008 1.282929 0.617201 -0.289492 0.019953 0.731340\n6961 27.961249 -0.005664 -1.030459 1.281961 0.621449 -0.283441 0.020346 0.730102\n6962 27.971100 -0.004251 -1.030854 1.281572 0.626918 -0.274611 0.022175 0.728746\n6963 27.979255 -0.003224 -1.030966 1.281422 0.631805 -0.268596 0.021677 0.726780\n6964 27.986004 -0.001994 -1.030847 1.281537 0.635546 -0.261747 0.022855 0.725980\n6965 27.994866 -0.001102 -1.030972 1.282181 0.638501 -0.250353 0.024332 0.727357\n6966 28.003446 0.001101 -1.030581 1.284171 0.643406 -0.241858 0.027947 0.725777\n6967 28.011021 0.001853 -1.029848 1.283716 0.643590 -0.236341 0.030360 0.727333\n6968 28.020636 0.003560 -1.029605 1.284841 0.644877 -0.227870 0.033657 0.728750\n6969 28.029419 0.004854 -1.028970 1.284807 0.643454 -0.220629 0.038170 0.732006\n6970 28.036378 0.005169 -1.027999 1.285162 0.640174 -0.215636 0.041823 0.736159\n6971 28.048434 0.007011 -1.027857 1.286416 0.639711 -0.210997 0.046352 0.737632\n6972 28.053508 0.008401 -1.026735 1.287107 0.635964 -0.203943 0.052230 0.742448\n6973 28.061009 0.009665 -1.025692 1.287428 0.632711 -0.201166 0.056752 0.745646\n6974 28.070923 0.011174 -1.024813 1.289004 0.630133 -0.194173 0.063338 0.749144\n6975 28.078870 0.011947 -1.023788 1.289539 0.626520 -0.191136 0.069634 0.752390\n6976 28.087235 0.013449 -1.022890 1.290498 0.623707 -0.184134 0.077540 0.755693\n6977 28.094287 0.015172 -1.021471 1.291624 0.620371 -0.179640 0.087271 0.758454\n6978 28.103381 0.016880 -1.019834 1.292909 0.617051 -0.174963 0.096880 0.761085\n6979 28.112310 0.018085 -1.018954 1.293529 0.612675 -0.168974 0.108084 0.764457\n6980 28.121037 0.018782 -1.017554 1.294660 0.606685 -0.162509 0.120056 0.768837\n6981 28.128446 0.020513 -1.016290 1.295955 0.602739 -0.156535 0.133935 0.770885\n6982 28.136036 0.021363 -1.014815 1.296935 0.596616 -0.152168 0.147964 0.773951\n6983 28.145928 0.022402 -1.013275 1.298256 0.590918 -0.145824 0.163942 0.776321\n6984 28.154138 0.023862 -1.011603 1.299859 0.585365 -0.139012 0.180081 0.778199\n6985 28.161828 0.024453 -1.010135 1.300780 0.580167 -0.134553 0.196131 0.778996\n6986 28.170545 0.025188 -1.008600 1.301973 0.574907 -0.128972 0.213286 0.779332\n6987 28.177832 0.026406 -1.006955 1.303223 0.570387 -0.121203 0.231425 0.778724\n6988 28.187944 0.027225 -1.005378 1.304511 0.565812 -0.115794 0.248493 0.777625\n6989 28.194791 0.027768 -1.003704 1.305833 0.561137 -0.110687 0.265265 0.776214\n6990 28.202819 0.029099 -1.001926 1.307061 0.557280 -0.102576 0.284137 0.773423\n6991 28.211022 0.029880 -1.000048 1.308527 0.552170 -0.095674 0.302416 0.771038\n6992 28.220551 0.029886 -0.998053 1.309956 0.546391 -0.092703 0.319186 0.768755\n6993 28.227756 0.030410 -0.996194 1.311640 0.538298 -0.083088 0.338695 0.767214\n6994 28.236990 0.031027 -0.993920 1.313066 0.529054 -0.075774 0.357964 0.765651\n6995 28.245634 0.030529 -0.992056 1.314438 0.518457 -0.071429 0.374857 0.765234\n6996 28.252629 0.030662 -0.989115 1.317037 0.509246 -0.068515 0.393652 0.762242\n6997 28.261050 0.031291 -0.986843 1.318439 0.496266 -0.059852 0.413903 0.760804\n6998 28.270168 0.030757 -0.984093 1.320392 0.481781 -0.057000 0.433301 0.759532\n6999 28.277671 0.029894 -0.981340 1.322313 0.467188 -0.055170 0.451834 0.757983\n7000 28.286043 0.029019 -0.978721 1.323887 0.451029 -0.052493 0.470965 0.756313\n7001 28.295894 0.028269 -0.975891 1.325598 0.434295 -0.048316 0.489675 0.754501\n7002 28.304170 0.027648 -0.973121 1.327332 0.418458 -0.041003 0.509799 0.750544\n7003 28.311577 0.025822 -0.970268 1.328897 0.402059 -0.040064 0.528309 0.746748\n7004 28.321189 0.024726 -0.968196 1.330360 0.386521 -0.034978 0.545527 0.742818\n7005 28.327540 0.024019 -0.965347 1.331834 0.370998 -0.026940 0.565042 0.736452\n7006 28.335994 0.022704 -0.962809 1.333146 0.356315 -0.020121 0.583241 0.729702\n7007 28.344475 0.020791 -0.960480 1.334770 0.342288 -0.015001 0.599868 0.723030\n7008 28.355389 0.019170 -0.958052 1.336179 0.327535 -0.006461 0.616482 0.715981\n7009 28.362753 0.018308 -0.955825 1.337240 0.314231 0.003517 0.633956 0.706644\n7010 28.371508 0.016787 -0.954075 1.338290 0.301454 0.010743 0.649399 0.698062\n7011 28.378184 0.015962 -0.951702 1.339169 0.286813 0.023274 0.665957 0.688257\n7012 28.385850 0.014343 -0.949843 1.340235 0.272411 0.033032 0.681206 0.678720\n7013 28.395572 0.011780 -0.948737 1.340849 0.257931 0.036530 0.696893 0.668189\n7014 28.403518 0.010838 -0.946186 1.342022 0.244004 0.048810 0.711600 0.657043\n7015 28.410969 0.009065 -0.944509 1.342875 0.229784 0.054999 0.726413 0.645367\n7016 28.419430 0.007346 -0.943462 1.343557 0.216781 0.057778 0.740109 0.633961\n7017 28.430886 0.005379 -0.941400 1.344305 0.200048 0.064746 0.754070 0.622227\n7018 28.437228 0.003138 -0.940093 1.344960 0.185863 0.065767 0.767580 0.609877\n7019 28.445634 0.001453 -0.938786 1.345424 0.171922 0.067404 0.779685 0.598323\n7020 28.454240 -0.000782 -0.937448 1.346091 0.158706 0.067974 0.789581 0.588858\n7021 28.462308 -0.003121 -0.937094 1.346110 0.144253 0.066305 0.802165 0.575609\n7022 28.470928 -0.005044 -0.936625 1.346342 0.133619 0.062357 0.812312 0.564276\n7023 28.478245 -0.006778 -0.935923 1.346639 0.121370 0.058577 0.822401 0.552716\n7024 28.486136 -0.009174 -0.935875 1.346956 0.111966 0.052704 0.830522 0.543064\n7025 28.497466 -0.011655 -0.935068 1.347259 0.099414 0.049367 0.839485 0.531925\n7026 28.503561 -0.013122 -0.934837 1.347635 0.091295 0.043806 0.846380 0.522864\n7027 28.512378 -0.015098 -0.934806 1.347805 0.082233 0.037645 0.853599 0.513020\n7028 28.520624 -0.016998 -0.935083 1.347894 0.074581 0.030317 0.860576 0.502918\n7029 28.527721 -0.019040 -0.935119 1.347958 0.065064 0.026395 0.867432 0.492577\n7030 28.537183 -0.020372 -0.935372 1.347993 0.056549 0.021167 0.873882 0.482373\n7031 28.545783 -0.022063 -0.935623 1.347993 0.047435 0.016980 0.880278 0.471776\n7032 28.553859 -0.023248 -0.936017 1.348003 0.039501 0.012428 0.886502 0.460868\n7033 28.562936 -0.025161 -0.936638 1.347849 0.029910 0.008343 0.892271 0.450432\n7034 28.571261 -0.025946 -0.936615 1.348044 0.020379 0.005985 0.898761 0.437924\n7035 28.579284 -0.027272 -0.936524 1.347878 0.009364 0.003856 0.904650 0.426036\n7036 28.586794 -0.029104 -0.936852 1.347942 -0.001912 0.002425 0.910681 0.413099\n7037 28.595501 -0.030340 -0.937041 1.347859 -0.012502 -0.000696 0.916201 0.400523\n7038 28.603757 -0.031453 -0.937463 1.347804 -0.020689 -0.004256 0.921265 0.388361\n7039 28.611010 -0.033355 -0.937804 1.347432 -0.038041 -0.006237 0.926374 0.374626\n7040 28.622193 -0.034446 -0.938501 1.346956 -0.042369 -0.010289 0.930824 0.362857\n7041 28.628064 -0.036117 -0.938211 1.346909 -0.053067 -0.013068 0.935276 0.349673\n7042 28.635817 -0.037269 -0.939614 1.346623 -0.062363 -0.017272 0.938421 0.339380\n7043 28.644592 -0.039342 -0.939149 1.346151 -0.073776 -0.018998 0.941869 0.327230\n7044 28.654637 -0.040386 -0.939874 1.345826 -0.080144 -0.025450 0.944766 0.316774\n7045 28.661321 -0.042170 -0.940289 1.345344 -0.089626 -0.028230 0.947173 0.306651\n7046 28.669529 -0.043460 -0.940922 1.344820 -0.098122 -0.034044 0.949176 0.297115\n7047 28.679158 -0.044715 -0.941884 1.344358 -0.105164 -0.041109 0.950865 0.288280\n7048 28.686104 -0.045787 -0.942617 1.343820 -0.112128 -0.047160 0.952242 0.280070\n7049 28.694455 -0.046914 -0.943648 1.343431 -0.117853 -0.053328 0.953383 0.272632\n7050 28.703586 -0.047994 -0.944560 1.342866 -0.124301 -0.060259 0.954114 0.265678\n7051 28.710961 -0.049097 -0.945454 1.342299 -0.130054 -0.067536 0.954607 0.259327\n7052 28.721347 -0.050056 -0.946259 1.341618 -0.135455 -0.074997 0.954844 0.253574\n7053 28.728234 -0.051266 -0.947511 1.340923 -0.140953 -0.082267 0.954906 0.248031\n7054 28.738076 -0.053091 -0.948578 1.340092 -0.147259 -0.089583 0.954713 0.242515\n7055 28.745301 -0.054117 -0.949733 1.339344 -0.151428 -0.096654 0.954504 0.238011\n7056 28.752900 -0.055197 -0.951033 1.338595 -0.154940 -0.104121 0.954255 0.233561\n7057 28.761983 -0.056158 -0.952401 1.337881 -0.158597 -0.110545 0.953897 0.229583\n7058 28.770448 -0.057205 -0.953488 1.337217 -0.160905 -0.117213 0.953661 0.225615\n7059 28.777653 -0.057973 -0.954957 1.336489 -0.165420 -0.122092 0.953053 0.222306\n7060 28.786317 -0.058935 -0.956326 1.335805 -0.167220 -0.129012 0.952674 0.218643\n7061 28.795451 -0.059983 -0.957672 1.335063 -0.169569 -0.135564 0.952054 0.215550\n7062 28.802469 -0.060291 -0.959334 1.334239 -0.169794 -0.145743 0.951182 0.212558\n7063 28.811104 -0.061391 -0.960432 1.333068 -0.177438 -0.153235 0.949139 0.210169\n7064 28.820211 -0.062254 -0.961956 1.332453 -0.175726 -0.162710 0.948466 0.207503\n7065 28.827628 -0.063283 -0.963310 1.331611 -0.178249 -0.171989 0.946900 0.205006\n7066 28.835915 -0.064136 -0.965191 1.330808 -0.178653 -0.181678 0.945297 0.203691\n7067 28.847906 -0.064953 -0.966408 1.330043 -0.179949 -0.191889 0.943779 0.200195\n7068 28.852819 -0.066321 -0.967436 1.329337 -0.182868 -0.200038 0.941893 0.198451\n7069 28.862321 -0.067281 -0.968924 1.328407 -0.183123 -0.209588 0.940110 0.196807\n7070 28.870408 -0.067974 -0.970437 1.327439 -0.182708 -0.219023 0.938236 0.195859\n7071 28.877613 -0.069386 -0.971609 1.326840 -0.185771 -0.226124 0.936563 0.192889\n7072 28.886939 -0.070451 -0.973018 1.325986 -0.187477 -0.234048 0.934663 0.190992\n7073 28.895427 -0.071385 -0.974527 1.324909 -0.188034 -0.242535 0.932761 0.189145\n7074 28.903889 -0.072338 -0.976202 1.323873 -0.190366 -0.249699 0.930774 0.187275\n7075 28.911881 -0.073811 -0.977232 1.322614 -0.194813 -0.256935 0.928246 0.185451\n7076 28.920553 -0.074701 -0.978671 1.321543 -0.195490 -0.264818 0.926167 0.184036\n7077 28.928740 -0.075677 -0.980226 1.320604 -0.195652 -0.272516 0.924160 0.182713\n7078 28.936561 -0.076910 -0.981842 1.319229 -0.196070 -0.281414 0.921649 0.181453\n7079 28.945638 -0.078624 -0.983372 1.318016 -0.196013 -0.290145 0.919253 0.179914\n7080 28.954101 -0.079673 -0.984940 1.316838 -0.197678 -0.298378 0.916357 0.179401\n7081 28.961079 -0.080660 -0.986741 1.315395 -0.196411 -0.307616 0.913649 0.179002\n7082 28.969397 -0.082053 -0.988381 1.313938 -0.195442 -0.316797 0.910756 0.178791\n7083 28.978908 -0.083226 -0.990169 1.312361 -0.194689 -0.325862 0.907794 0.178383\n7084 28.987085 -0.084647 -0.991908 1.310933 -0.194580 -0.334756 0.904514 0.178693\n7085 28.995518 -0.085640 -0.993757 1.309407 -0.192744 -0.344353 0.901200 0.179191\n7086 29.004037 -0.087014 -0.995432 1.307882 -0.192970 -0.353439 0.897815 0.178250\n7087 29.011068 -0.088088 -0.997079 1.306352 -0.192742 -0.362248 0.894397 0.177994\n7088 29.020655 -0.089021 -0.998751 1.304879 -0.192252 -0.370994 0.890921 0.177940\n7089 29.028912 -0.090227 -1.000281 1.303371 -0.192931 -0.378999 0.887557 0.177146\n7090 29.036110 -0.091468 -1.001788 1.301815 -0.194047 -0.385877 0.884541 0.176161\n7091 29.044977 -0.092873 -1.003254 1.300348 -0.195659 -0.392081 0.881647 0.175179\n7092 29.054464 -0.094036 -1.004627 1.298828 -0.196343 -0.398484 0.878766 0.174442\n7093 29.060863 -0.095286 -1.005937 1.297351 -0.197683 -0.404343 0.875989 0.173415\n7094 29.070633 -0.096428 -1.007171 1.295981 -0.198164 -0.410640 0.873241 0.171917\n7095 29.078500 -0.097333 -1.008310 1.294684 -0.197641 -0.417679 0.870133 0.171321\n7096 29.085804 -0.098187 -1.009526 1.293304 -0.197776 -0.424856 0.867185 0.168443\n7097 29.094663 -0.099237 -1.010735 1.291783 -0.196426 -0.432038 0.864510 0.165477\n7098 29.103553 -0.100145 -1.011899 1.290708 -0.196090 -0.437855 0.861998 0.163684\n7099 29.111023 -0.101189 -1.013083 1.289645 -0.194008 -0.441761 0.860731 0.162330\n7100 29.119152 -0.102323 -1.014127 1.288649 -0.192242 -0.444857 0.859771 0.161057\n7101 29.128802 -0.103127 -1.015151 1.287799 -0.190221 -0.446894 0.859453 0.159509\n7102 29.136539 -0.103659 -1.016138 1.287094 -0.188515 -0.449310 0.858860 0.157929\n7103 29.145369 -0.103929 -1.016936 1.286489 -0.185899 -0.451227 0.858667 0.156611\n7104 29.153418 -0.104763 -1.017719 1.285796 -0.185527 -0.453515 0.857620 0.156177\n7105 29.161052 -0.105364 -1.018516 1.285245 -0.186492 -0.454141 0.857127 0.155919\n7106 29.170750 -0.105939 -1.019300 1.284608 -0.186229 -0.455198 0.856592 0.156088\n7107 29.178797 -0.106719 -1.019658 1.284257 -0.188309 -0.454150 0.856783 0.155597\n7108 29.187820 -0.107089 -1.020047 1.284116 -0.189167 -0.452758 0.857306 0.155732\n7109 29.195931 -0.107501 -1.020323 1.284102 -0.190296 -0.450916 0.857938 0.156224\n7110 29.203210 -0.107882 -1.020598 1.284165 -0.191853 -0.447858 0.859150 0.156450\n7111 29.212766 -0.108330 -1.020639 1.284308 -0.193361 -0.444699 0.860558 0.155865\n7112 29.220380 -0.108387 -1.020639 1.284585 -0.193325 -0.442022 0.861810 0.156607\n7113 29.228908 -0.108553 -1.020566 1.284824 -0.194248 -0.439478 0.863018 0.155973\n7114 29.236908 -0.108602 -1.020406 1.285248 -0.194720 -0.437651 0.863957 0.155315\n7115 29.244325 -0.108569 -1.020144 1.285773 -0.194963 -0.435918 0.864861 0.154856\n7116 29.254296 -0.108230 -1.019790 1.286275 -0.193717 -0.434719 0.865801 0.154540\n7117 29.262348 -0.107773 -1.019073 1.287144 -0.191686 -0.433133 0.867077 0.154368\n7118 29.269246 -0.107478 -1.018814 1.288087 -0.191130 -0.430292 0.868762 0.153529\n7119 29.279013 -0.106882 -1.018098 1.289224 -0.188662 -0.427069 0.870917 0.153369\n7120 29.286816 -0.106661 -1.017247 1.290519 -0.188717 -0.421944 0.873507 0.152759\n7121 29.295709 -0.106124 -1.016080 1.292071 -0.187433 -0.415505 0.877053 0.151669\n7122 29.304338 -0.105520 -1.014879 1.293942 -0.186968 -0.407262 0.881150 0.150850\n7123 29.310994 -0.105443 -1.013334 1.295817 -0.187934 -0.396691 0.885994 0.149436\n7124 29.320424 -0.104921 -1.011473 1.297875 -0.187820 -0.384913 0.891550 0.147323\n7125 29.328611 -0.104584 -1.009719 1.300112 -0.190588 -0.370946 0.897081 0.146017\n7126 29.336397 -0.103910 -1.007665 1.302470 -0.191481 -0.356272 0.902958 0.145162\n7127 29.344342 -0.103552 -1.005534 1.304763 -0.193337 -0.340172 0.908824 0.144721\n7128 29.353911 -0.102736 -1.003063 1.307352 -0.194896 -0.323706 0.914442 0.145001\n7129 29.362271 -0.102367 -1.000871 1.309517 -0.198060 -0.306828 0.919488 0.145500\n7130 29.369210 -0.101571 -0.998506 1.311790 -0.199346 -0.291172 0.923943 0.147678\n7131 29.377570 -0.100693 -0.996067 1.313995 -0.200580 -0.276103 0.928226 0.148094\n7132 29.387069 -0.099647 -0.993713 1.316108 -0.201664 -0.261799 0.931720 0.150636\n7133 29.394252 -0.098808 -0.991160 1.318049 -0.202112 -0.248674 0.934756 0.153438\n7134 29.402647 -0.097738 -0.988972 1.320029 -0.201071 -0.235721 0.938165 0.154441\n7135 29.412937 -0.096559 -0.987009 1.322369 -0.195433 -0.223622 0.941618 0.158602\n7136 29.419644 -0.095666 -0.984663 1.324179 -0.191899 -0.210671 0.945109 0.159879\n7137 29.429039 -0.094672 -0.982818 1.326089 -0.187612 -0.197677 0.948401 0.162050\n7138 29.437134 -0.093827 -0.980345 1.327850 -0.183742 -0.183585 0.951784 0.163225\n7139 29.444188 -0.093172 -0.977719 1.329803 -0.181139 -0.169811 0.954968 0.162448\n7140 29.452485 -0.091922 -0.975558 1.331790 -0.172891 -0.155765 0.959120 0.161041\n7141 29.462382 -0.090988 -0.973071 1.333747 -0.169739 -0.141767 0.962155 0.159211\n7142 29.470218 -0.089602 -0.970865 1.335619 -0.164703 -0.129068 0.965352 0.155919\n7143 29.478931 -0.088167 -0.968613 1.337678 -0.162042 -0.116353 0.968119 0.151494\n7144 29.487039 -0.086783 -0.965923 1.339147 -0.157872 -0.103272 0.970473 0.150310\n7145 29.494143 -0.085106 -0.962891 1.341591 -0.156222 -0.092419 0.972211 0.147848\n7146 29.502429 -0.084223 -0.960761 1.343147 -0.155234 -0.080461 0.973981 0.144184\n7147 29.512444 -0.082478 -0.958206 1.345048 -0.149210 -0.069267 0.975948 0.143051\n7148 29.520772 -0.081530 -0.955927 1.346517 -0.146647 -0.056956 0.977681 0.139251\n7149 29.528940 -0.080449 -0.952568 1.347976 -0.146152 -0.045380 0.978477 0.138430\n7150 29.537521 -0.079443 -0.950679 1.349567 -0.142838 -0.033436 0.979994 0.134505\n7151 29.544462 -0.078440 -0.947803 1.351038 -0.140872 -0.020162 0.980934 0.132355\n7152 29.555168 -0.077303 -0.944634 1.352344 -0.139524 -0.005435 0.981562 0.130535\n7153 29.561248 -0.076914 -0.941666 1.353744 -0.140189 0.010728 0.981737 0.128157\n7154 29.570491 -0.075607 -0.938760 1.355371 -0.138792 0.022786 0.981981 0.126216\n7155 29.577504 -0.074969 -0.935857 1.356667 -0.140213 0.041920 0.981460 0.123771\n7156 29.587513 -0.073561 -0.932807 1.357917 -0.135277 0.055417 0.981449 0.124044\n7157 29.594234 -0.072229 -0.929833 1.359173 -0.132992 0.070909 0.980864 0.123255\n7158 29.603214 -0.070709 -0.927097 1.360287 -0.130718 0.085627 0.980092 0.122477\n7159 29.612547 -0.069525 -0.924033 1.361439 -0.131671 0.098506 0.978674 0.123112\n7160 29.620812 -0.068302 -0.921223 1.362576 -0.129607 0.111342 0.977473 0.123905\n7161 29.628381 -0.066949 -0.918512 1.363560 -0.125852 0.123391 0.976368 0.125068\n7162 29.638504 -0.065563 -0.915933 1.364535 -0.121658 0.135189 0.975142 0.126578\n7163 29.644935 -0.063584 -0.913762 1.365374 -0.114183 0.149337 0.973530 0.130002\n7164 29.652751 -0.062222 -0.911046 1.366261 -0.110883 0.161926 0.971712 0.131377\n7165 29.662221 -0.061412 -0.907921 1.367063 -0.108356 0.175291 0.969658 0.131512\n7166 29.670702 -0.059998 -0.905035 1.367921 -0.104526 0.188537 0.967500 0.132181\n7167 29.677743 -0.058527 -0.902233 1.368650 -0.096874 0.204226 0.965014 0.132875\n7168 29.685984 -0.057249 -0.899253 1.369064 -0.096351 0.219061 0.961744 0.133335\n7169 29.696011 -0.055574 -0.896543 1.370068 -0.095061 0.231926 0.958961 0.132542\n7170 29.703664 -0.053732 -0.893277 1.370201 -0.086559 0.248430 0.955776 0.131462\n7171 29.711208 -0.052072 -0.890708 1.370857 -0.080765 0.262764 0.952523 0.130887\n7172 29.720751 -0.051100 -0.887862 1.371542 -0.079902 0.275998 0.948797 0.131245\n7173 29.727780 -0.049899 -0.885157 1.371616 -0.076291 0.290522 0.944822 0.130719\n7174 29.737749 -0.048491 -0.882735 1.372411 -0.073959 0.301579 0.941512 0.130899\n7175 29.745077 -0.047159 -0.880374 1.372852 -0.071796 0.313240 0.937935 0.130400\n7176 29.752541 -0.045550 -0.878000 1.373232 -0.065854 0.327751 0.933217 0.131718\n7177 29.761513 -0.044780 -0.875817 1.373113 -0.061945 0.339489 0.929088 0.133060\n7178 29.770409 -0.043642 -0.873619 1.373562 -0.059241 0.350266 0.925235 0.133209\n7179 29.777633 -0.043102 -0.870897 1.373681 -0.057184 0.361113 0.920935 0.134932\n7180 29.786009 -0.041788 -0.868587 1.373907 -0.054504 0.374087 0.915789 0.135717\n7181 29.795724 -0.040410 -0.866251 1.374186 -0.050780 0.386132 0.911208 0.134250\n7182 29.803066 -0.039212 -0.864234 1.374089 -0.049466 0.399074 0.905386 0.136267\n7183 29.812268 -0.037674 -0.861886 1.374161 -0.046063 0.409568 0.900873 0.136233\n7184 29.820908 -0.036563 -0.859822 1.374285 -0.042903 0.421191 0.895553 0.136904\n7185 29.827707 -0.034914 -0.857933 1.374399 -0.039716 0.429962 0.891539 0.136797\n7186 29.835937 -0.033634 -0.855896 1.374401 -0.037149 0.438046 0.887709 0.136776\n7187 29.845937 -0.032193 -0.853985 1.374560 -0.032847 0.446248 0.883806 0.136641\n7188 29.853353 -0.030828 -0.852288 1.374476 -0.029767 0.451346 0.881455 0.135788\n7189 29.862165 -0.029229 -0.850384 1.374706 -0.024453 0.458990 0.878025 0.133423\n7190 29.870903 -0.028147 -0.848730 1.374780 -0.020984 0.464123 0.875576 0.132351\n7191 29.877761 -0.027155 -0.847452 1.374835 -0.017443 0.467891 0.873864 0.130902\n7192 29.887794 -0.025802 -0.845873 1.374840 -0.014509 0.471632 0.872129 0.129398\n7193 29.895056 -0.024852 -0.844710 1.375033 -0.010911 0.474544 0.870889 0.127441\n7194 29.902595 -0.023896 -0.843530 1.375112 -0.006913 0.478000 0.869362 0.125210\n7195 29.911394 -0.022834 -0.842646 1.375453 -0.003921 0.479529 0.868794 0.123422\n7196 29.921182 -0.021758 -0.841918 1.375376 -0.001038 0.480574 0.868566 0.120995\n7197 29.928593 -0.020996 -0.841018 1.375415 0.000774 0.483406 0.867419 0.117912\n7198 29.936844 -0.020382 -0.840255 1.375415 0.002139 0.486000 0.866304 0.115396\n7199 29.945533 -0.019671 -0.839566 1.375692 0.004254 0.488297 0.865433 0.112129\n7200 29.952575 -0.019019 -0.838888 1.375141 0.006123 0.488847 0.865440 0.109563\n7201 29.960876 -0.018320 -0.838489 1.375533 0.006569 0.490657 0.864712 0.107167\n7202 29.969385 -0.017547 -0.838022 1.375467 0.006381 0.490754 0.864881 0.105363\n7203 29.979080 -0.016776 -0.837490 1.375408 0.009481 0.492143 0.864262 0.103718\n7204 29.987364 -0.016215 -0.837462 1.375640 0.009006 0.493514 0.863852 0.100611\n7205 29.995602 -0.015887 -0.837000 1.375620 0.008330 0.494126 0.863739 0.098612\n7206 30.004390 -0.015592 -0.836938 1.375323 0.010663 0.494111 0.863928 0.096796\n7207 30.010932 -0.014918 -0.837192 1.375862 0.010584 0.492129 0.865130 0.096167\n7208 30.020626 -0.014508 -0.837384 1.376020 0.012131 0.490386 0.866095 0.096194\n7209 30.028375 -0.014468 -0.837730 1.376133 0.011008 0.487348 0.867979 0.094778\n7210 30.035860 -0.014023 -0.838170 1.376456 0.013260 0.483358 0.870114 0.095350\n7211 30.044346 -0.013842 -0.838736 1.376697 0.014794 0.479567 0.872098 0.096133\n7212 30.054710 -0.014129 -0.839302 1.376697 0.016780 0.476747 0.873496 0.097131\n7213 30.060866 -0.013800 -0.839790 1.377148 0.017341 0.472546 0.875760 0.097179\n7214 30.071250 -0.013840 -0.840298 1.377295 0.018467 0.469166 0.877483 0.097807\n7215 30.078779 -0.013845 -0.840893 1.377558 0.018985 0.465834 0.879186 0.098342\n7216 30.087175 -0.013789 -0.841604 1.377612 0.019900 0.461482 0.881380 0.099032\n7217 30.094293 -0.013859 -0.842310 1.378009 0.018891 0.457764 0.883245 0.099869\n7218 30.104687 -0.013931 -0.843261 1.378235 0.018445 0.452572 0.885777 0.101179\n7219 30.110978 -0.014216 -0.844497 1.378476 0.019276 0.446958 0.888424 0.102756\n7220 30.119488 -0.014516 -0.845733 1.378837 0.018406 0.441127 0.891081 0.105084\n7221 30.130093 -0.014661 -0.847103 1.379212 0.017267 0.434560 0.893937 0.108333\n7222 30.136623 -0.014996 -0.848366 1.379472 0.017372 0.427184 0.897119 0.111309\n7223 30.146353 -0.015864 -0.849568 1.379669 0.015776 0.420317 0.899928 0.114954\n7224 30.153134 -0.016528 -0.850970 1.379897 0.015007 0.412418 0.903004 0.119454\n7225 30.162375 -0.017237 -0.852756 1.380417 0.015959 0.404621 0.905798 0.124731\n7226 30.171043 -0.018068 -0.854182 1.380318 0.014966 0.397057 0.908338 0.130553\n7227 30.177873 -0.019096 -0.855584 1.380321 0.012895 0.388424 0.911224 0.136497\n7228 30.187545 -0.020027 -0.857335 1.380544 0.010438 0.379697 0.913976 0.142721\n7229 30.194819 -0.021057 -0.859038 1.380645 0.007803 0.373986 0.915183 0.150045\n7230 30.202906 -0.022092 -0.860637 1.380495 0.008156 0.367603 0.916808 0.155767\n7231 30.210992 -0.022980 -0.862764 1.380533 0.007696 0.362293 0.917789 0.162323\n7232 30.219778 -0.024238 -0.864317 1.380303 0.004357 0.356098 0.918977 0.169280\n7233 30.229102 -0.025624 -0.866047 1.380452 -0.000893 0.349226 0.920220 0.176737\n7234 30.235727 -0.028076 -0.867423 1.380509 -0.001502 0.344081 0.920676 0.184289\n7235 30.245627 -0.028454 -0.870199 1.380111 -0.004037 0.337655 0.922139 0.188765\n7236 30.253021 -0.030030 -0.871964 1.379772 -0.009259 0.330051 0.922880 0.198173\n7237 30.262030 -0.031822 -0.873785 1.379247 -0.010364 0.323097 0.923816 0.205098\n7238 30.270259 -0.033209 -0.876139 1.379114 -0.013701 0.313727 0.925091 0.213531\n7239 30.278925 -0.034074 -0.878348 1.378586 -0.017521 0.304442 0.926332 0.221175\n7240 30.287383 -0.035751 -0.880751 1.378194 -0.019257 0.296871 0.926468 0.230552\n7241 30.294807 -0.037880 -0.882519 1.377743 -0.023771 0.286211 0.928118 0.236886\n7242 30.304465 -0.038517 -0.884483 1.377194 -0.023982 0.277733 0.928334 0.245938\n7243 30.310992 -0.040635 -0.887052 1.377136 -0.024965 0.268814 0.928678 0.254310\n7244 30.319570 -0.041182 -0.888667 1.376666 -0.030718 0.257401 0.929319 0.262998\n7245 30.328437 -0.042246 -0.891342 1.375671 -0.026603 0.251131 0.927951 0.274103\n7246 30.336397 -0.043755 -0.893754 1.375472 -0.023809 0.241580 0.928089 0.282351\n7247 30.344931 -0.044671 -0.896158 1.375077 -0.021621 0.232538 0.927443 0.292075\n7248 30.352633 -0.045697 -0.898574 1.374346 -0.020685 0.224027 0.926638 0.301209\n7249 30.362125 -0.046831 -0.901091 1.373731 -0.018659 0.215799 0.925696 0.310111\n7250 30.369658 -0.047917 -0.903613 1.372998 -0.015566 0.207132 0.924542 0.319494\n7251 30.377545 -0.048813 -0.906073 1.372310 -0.012866 0.199486 0.923083 0.328569\n7252 30.387072 -0.049694 -0.908552 1.371599 -0.009026 0.191135 0.921354 0.338367\n7253 30.394831 -0.050894 -0.910909 1.370867 -0.003124 0.181647 0.919638 0.348225\n7254 30.402550 -0.051394 -0.913378 1.370170 0.000160 0.173115 0.916832 0.359793\n7255 30.410961 -0.052554 -0.915384 1.369422 0.007341 0.164117 0.913863 0.371303\n7256 30.419373 -0.053434 -0.917494 1.368699 0.013697 0.155343 0.910819 0.382216\n7257 30.428377 -0.054020 -0.919664 1.367973 0.022016 0.147426 0.906058 0.396029\n7258 30.435894 -0.055196 -0.921477 1.367235 0.028006 0.139857 0.902142 0.407179\n7259 30.444187 -0.055940 -0.923220 1.366431 0.037570 0.133499 0.896547 0.420678\n7260 30.452683 -0.056617 -0.925081 1.365692 0.046366 0.127329 0.890821 0.433677\n7261 30.462225 -0.057292 -0.926665 1.364929 0.054498 0.122377 0.884690 0.446517\n7262 30.470104 -0.057772 -0.928448 1.364227 0.066358 0.116402 0.877842 0.459827\n7263 30.478853 -0.058645 -0.930078 1.363554 0.070613 0.111150 0.871862 0.471717\n7264 30.487406 -0.058810 -0.932427 1.362945 0.083374 0.105017 0.863551 0.486106\n7265 30.494536 -0.059392 -0.933190 1.362085 0.098130 0.099610 0.856243 0.497289\n7266 30.503875 -0.059504 -0.934436 1.361321 0.110961 0.094943 0.848012 0.509459\n7267 30.511964 -0.059674 -0.936413 1.360688 0.123805 0.088736 0.839450 0.521653\n7268 30.521119 -0.059729 -0.938113 1.360126 0.136480 0.084696 0.830437 0.533455\n7269 30.529093 -0.059173 -0.939270 1.359634 0.152293 0.079933 0.820234 0.545558\n7270 30.537124 -0.059289 -0.941609 1.359193 0.163615 0.076439 0.811135 0.556280\n7271 30.545695 -0.059008 -0.942281 1.358940 0.176952 0.073409 0.800777 0.567499\n7272 30.554036 -0.058491 -0.944097 1.358711 0.196279 0.068272 0.789518 0.577473\n7273 30.562077 -0.057445 -0.945135 1.358206 0.208947 0.065171 0.779341 0.587130\n7274 30.571186 -0.056524 -0.946391 1.358198 0.223209 0.063011 0.767852 0.597168\n7275 30.578172 -0.055721 -0.947797 1.357893 0.236902 0.061402 0.756366 0.606645\n7276 30.586025 -0.054955 -0.949498 1.357557 0.251537 0.058341 0.744366 0.615828\n7277 30.595514 -0.054007 -0.951369 1.357099 0.267017 0.054179 0.731300 0.625274\n7278 30.603279 -0.053224 -0.952945 1.356654 0.280728 0.050732 0.717984 0.634915\n7279 30.612228 -0.052432 -0.954360 1.356225 0.292613 0.048616 0.704526 0.644715\n7280 30.620266 -0.051382 -0.955850 1.355619 0.306482 0.044741 0.690132 0.654052\n7281 30.628662 -0.050614 -0.957931 1.354735 0.319822 0.037498 0.674587 0.664259\n7282 30.636929 -0.049486 -0.959348 1.354525 0.333521 0.034465 0.658702 0.673563\n7283 30.644860 -0.048631 -0.961058 1.353917 0.346759 0.029214 0.641912 0.683267\n7284 30.652530 -0.047572 -0.962563 1.353271 0.360141 0.024987 0.625170 0.691980\n7285 30.662245 -0.046885 -0.964588 1.352557 0.374253 0.015629 0.606739 0.701112\n7286 30.670587 -0.045981 -0.966112 1.351824 0.386164 0.009973 0.588774 0.710017\n7287 30.677749 -0.045021 -0.967803 1.351208 0.394392 0.005058 0.570782 0.720165\n7288 30.685774 -0.043927 -0.968990 1.350521 0.404398 0.000758 0.553250 0.728270\n7289 30.695550 -0.043256 -0.970470 1.349567 0.413064 -0.003643 0.533615 0.737984\n7290 30.703398 -0.042290 -0.972114 1.348827 0.421805 -0.006956 0.514264 0.746703\n7291 30.710931 -0.042327 -0.973348 1.348006 0.431680 -0.015997 0.495408 0.753636\n7292 30.720246 -0.040781 -0.975187 1.346922 0.437787 -0.016398 0.478021 0.761295\n7293 30.729250 -0.040901 -0.976920 1.346001 0.443330 -0.024701 0.457760 0.770263\n7294 30.737339 -0.039747 -0.978589 1.345030 0.449636 -0.027725 0.438680 0.777572\n7295 30.744661 -0.039307 -0.979807 1.344207 0.456044 -0.033108 0.419297 0.784295\n7296 30.752875 -0.038086 -0.981571 1.343140 0.461881 -0.036394 0.401631 0.789958\n7297 30.761943 -0.037703 -0.983030 1.342270 0.467994 -0.041455 0.382373 0.795647\n7298 30.769779 -0.036639 -0.984073 1.341605 0.474215 -0.044358 0.363528 0.800625\n7299 30.778550 -0.036167 -0.985943 1.340108 0.479145 -0.050163 0.343752 0.806063\n7300 30.785795 -0.035005 -0.987066 1.339458 0.484738 -0.051905 0.324697 0.810498\n7301 30.795521 -0.034481 -0.988469 1.338433 0.489434 -0.057584 0.304864 0.814983\n7302 30.803402 -0.034012 -0.989741 1.337394 0.493652 -0.063785 0.284884 0.819195\n7303 30.812171 -0.033602 -0.991106 1.336341 0.497295 -0.068934 0.263774 0.823632\n7304 30.819801 -0.033595 -0.992379 1.335254 0.500039 -0.076501 0.242691 0.827774\n7305 30.828329 -0.033184 -0.993424 1.334359 0.502885 -0.081672 0.221386 0.831519\n7306 30.836940 -0.032602 -0.994556 1.333318 0.505388 -0.087342 0.200863 0.834630\n7307 30.844823 -0.033047 -0.995542 1.332376 0.505265 -0.096437 0.178796 0.838712\n7308 30.852456 -0.032630 -0.996536 1.331365 0.507509 -0.105010 0.158429 0.840421\n7309 30.860984 -0.032984 -0.997477 1.330908 0.506481 -0.110488 0.138287 0.843888\n7310 30.871192 -0.033019 -0.998382 1.329911 0.506560 -0.118326 0.118243 0.845822\n7311 30.877985 -0.033096 -0.999384 1.329155 0.507754 -0.126160 0.097899 0.846573\n7312 30.886456 -0.033473 -1.000253 1.327921 0.507630 -0.134558 0.078388 0.847385\n7313 30.895139 -0.033929 -1.001100 1.327484 0.508914 -0.142831 0.059197 0.846818\n7314 30.902528 -0.034377 -1.002015 1.326593 0.510075 -0.150273 0.039636 0.845973\n7315 30.911919 -0.035155 -1.002983 1.325268 0.511061 -0.156177 0.020429 0.844990\n7316 30.919861 -0.035957 -1.003855 1.324297 0.515057 -0.165783 0.001923 0.840969\n7317 30.929400 -0.036453 -1.004848 1.323007 0.518094 -0.173078 -0.016376 0.837469\n7318 30.937209 -0.037291 -1.005633 1.322409 0.521083 -0.178344 -0.034684 0.833944\n7319 30.945210 -0.038151 -1.006340 1.321173 0.523635 -0.186555 -0.053281 0.829557\n7320 30.956699 -0.038780 -1.006934 1.320390 0.526044 -0.193190 -0.070305 0.825235\n7321 30.962018 -0.039873 -1.007417 1.319455 0.527621 -0.199074 -0.086945 0.821235\n7322 30.970299 -0.040410 -1.008066 1.318409 0.528992 -0.206109 -0.102227 0.816846\n7323 30.978860 -0.041743 -1.008504 1.317602 0.529487 -0.211777 -0.118256 0.812902\n7324 30.986882 -0.043025 -1.009041 1.316602 0.531120 -0.218348 -0.131541 0.808043\n7325 30.995132 -0.044320 -1.009246 1.315943 0.531583 -0.224168 -0.145898 0.803668\n7326 31.002947 -0.045852 -1.009719 1.314941 0.534115 -0.229294 -0.157441 0.798347\n7327 31.011890 -0.047016 -1.010377 1.313691 0.536920 -0.233626 -0.167618 0.793120\n7328 31.021233 -0.048778 -1.011055 1.312716 0.541559 -0.238003 -0.177114 0.786574\n7329 31.028025 -0.049521 -1.012022 1.311209 0.546709 -0.242102 -0.183327 0.780313\n7330 31.036647 -0.050578 -1.013042 1.309947 0.552563 -0.246496 -0.188104 0.773648\n7331 31.044791 -0.051684 -1.014131 1.307747 0.559707 -0.251015 -0.191567 0.766174\n7332 31.052661 -0.052416 -1.015431 1.306146 0.567757 -0.252671 -0.193251 0.759252\n7333 31.062074 -0.053062 -1.016662 1.304439 0.576271 -0.253799 -0.192747 0.752560\n7334 31.070056 -0.053871 -1.017695 1.302530 0.584810 -0.255092 -0.190880 0.745982\n7335 31.077584 -0.054432 -1.018925 1.301129 0.593063 -0.256122 -0.187543 0.739936\n7336 31.086702 -0.055470 -1.019693 1.299570 0.600319 -0.255250 -0.181487 0.735885\n7337 31.095797 -0.055026 -1.021123 1.297791 0.608068 -0.254557 -0.174563 0.731425\n7338 31.102414 -0.055101 -1.022205 1.296535 0.614235 -0.253718 -0.166034 0.728543\n7339 31.112755 -0.054894 -1.023245 1.294994 0.619357 -0.252425 -0.155892 0.726895\n7340 31.119548 -0.054806 -1.024240 1.293477 0.623580 -0.251339 -0.144791 0.725956\n7341 31.128724 -0.054094 -1.025181 1.292320 0.627504 -0.250426 -0.133081 0.725131\n7342 31.136737 -0.053721 -1.025973 1.291602 0.630830 -0.250066 -0.121163 0.724459\n7343 31.145404 -0.052309 -1.026841 1.290622 0.634432 -0.248782 -0.107905 0.723851\n7344 31.154681 -0.051137 -1.027782 1.289822 0.638696 -0.244896 -0.093350 0.723450\n7345 31.161634 -0.050238 -1.028089 1.290381 0.641424 -0.239114 -0.078687 0.724712\n7346 31.171132 -0.048416 -1.028908 1.289024 0.644826 -0.235195 -0.063907 0.724430\n7347 31.178170 -0.047143 -1.029085 1.288817 0.647706 -0.229920 -0.047365 0.724824\n7348 31.185690 -0.045223 -1.029339 1.288660 0.649741 -0.224921 -0.032048 0.725411\n7349 31.194307 -0.043407 -1.029552 1.288581 0.652017 -0.217234 -0.016002 0.726242\n7350 31.204657 -0.041461 -1.029673 1.288025 0.654174 -0.208541 0.001426 0.727025\n7351 31.211782 -0.039876 -1.029697 1.288909 0.654839 -0.199382 0.016433 0.728809\n7352 31.220268 -0.038175 -1.029705 1.288941 0.657857 -0.190351 0.034334 0.727882\n7353 31.228143 -0.035509 -1.029521 1.289135 0.659674 -0.180369 0.052397 0.727703\n7354 31.235788 -0.033930 -1.029114 1.289774 0.659482 -0.170331 0.069383 0.728874\n7355 31.245612 -0.031998 -1.028310 1.290645 0.659695 -0.156987 0.087538 0.729722\n7356 31.253122 -0.029373 -1.027839 1.291530 0.661811 -0.145702 0.106974 0.727554\n7357 31.262285 -0.027185 -1.026859 1.292961 0.661036 -0.133841 0.127399 0.727246\n7358 31.271399 -0.024316 -1.025648 1.294811 0.660429 -0.119664 0.149519 0.726057\n7359 31.278707 -0.022523 -1.023945 1.295579 0.658056 -0.106186 0.172311 0.725256\n7360 31.285827 -0.020985 -1.022350 1.297416 0.654862 -0.096087 0.194240 0.724012\n7361 31.294065 -0.018322 -1.020361 1.299034 0.651100 -0.081326 0.217206 0.722687\n7362 31.304440 -0.016468 -1.018592 1.301056 0.644891 -0.073074 0.240405 0.721791\n7363 31.312419 -0.014719 -1.016244 1.302749 0.638532 -0.062763 0.263551 0.720332\n7364 31.321069 -0.012683 -1.013932 1.304643 0.629457 -0.054349 0.288744 0.719345\n7365 31.328539 -0.010979 -1.011310 1.307063 0.618445 -0.043266 0.314829 0.718705\n7366 31.335847 -0.009464 -1.008974 1.308521 0.608613 -0.036516 0.341963 0.715065\n7367 31.345438 -0.008329 -1.006811 1.310105 0.598111 -0.033525 0.366124 0.712105\n7368 31.355504 -0.007411 -1.004748 1.311463 0.586643 -0.029173 0.390235 0.709024\n7369 31.361840 -0.006997 -1.002775 1.313282 0.579068 -0.026823 0.414469 0.701552\n7370 31.369452 -0.006066 -0.999920 1.315993 0.568469 -0.021846 0.441596 0.693800\n7371 31.379848 -0.005870 -0.998299 1.317371 0.560962 -0.020029 0.464426 0.685003\n7372 31.387262 -0.004744 -0.996483 1.318776 0.551964 -0.017480 0.488835 0.675330\n7373 31.395559 -0.004448 -0.994569 1.320288 0.546786 -0.015462 0.509975 0.663861\n7374 31.404785 -0.004653 -0.992653 1.321718 0.537100 -0.013038 0.533002 0.653653\n7375 31.411672 -0.004138 -0.990845 1.323055 0.529520 -0.008992 0.555605 0.640961\n7376 31.421265 -0.003873 -0.989626 1.324342 0.523126 -0.007072 0.576093 0.628017\n7377 31.428748 -0.004334 -0.987930 1.325537 0.512189 -0.003122 0.599254 0.615263\n7378 31.436356 -0.004604 -0.986351 1.326329 0.503394 -0.001750 0.620491 0.601317\n7379 31.445089 -0.004685 -0.984407 1.327999 0.492722 0.000600 0.642052 0.587361\n7380 31.454075 -0.004989 -0.983120 1.329345 0.481628 0.003975 0.663601 0.572409\n7381 31.461523 -0.005558 -0.982112 1.330371 0.471372 0.006238 0.682818 0.558148\n7382 31.470718 -0.006409 -0.980366 1.331572 0.458287 0.008983 0.703653 0.542922\n7383 31.478427 -0.007198 -0.978962 1.332474 0.446719 0.011601 0.721742 0.528579\n7384 31.486397 -0.008364 -0.978417 1.333211 0.437868 0.012074 0.739581 0.511024\n7385 31.496239 -0.009012 -0.976934 1.334938 0.420968 0.015860 0.757773 0.498312\n7386 31.502890 -0.010189 -0.974717 1.335472 0.404746 0.018958 0.776584 0.482429\n7387 31.510830 -0.011074 -0.973951 1.335965 0.393114 0.020111 0.792384 0.466031\n7388 31.520614 -0.012732 -0.972353 1.336512 0.375595 0.026559 0.808128 0.452938\n7389 31.528979 -0.013765 -0.971738 1.337549 0.365692 0.022948 0.821193 0.437476\n7390 31.536601 -0.015721 -0.970899 1.338042 0.350158 0.022872 0.835653 0.422552\n7391 31.545265 -0.016909 -0.970530 1.338548 0.337116 0.020669 0.847389 0.409705\n7392 31.552888 -0.018562 -0.969501 1.338741 0.323918 0.018599 0.859898 0.394089\n7393 31.561934 -0.020535 -0.968978 1.338839 0.310751 0.016351 0.871694 0.378570\n7394 31.570278 -0.022117 -0.968639 1.339076 0.298290 0.013163 0.882712 0.362863\n7395 31.578340 -0.023861 -0.968698 1.339179 0.284633 0.008646 0.892997 0.348520\n7396 31.586032 -0.025445 -0.967887 1.339288 0.270127 0.005234 0.903296 0.333257\n7397 31.596186 -0.027423 -0.968451 1.339202 0.255858 0.000115 0.912631 0.318814\n7398 31.603320 -0.028595 -0.968331 1.339221 0.244106 -0.004303 0.921422 0.302283\n7399 31.611035 -0.029741 -0.968195 1.339418 0.229981 -0.008064 0.929630 0.287805\n7400 31.620366 -0.031258 -0.968134 1.339299 0.218898 -0.011296 0.937037 0.271878\n7401 31.629014 -0.032825 -0.968334 1.339179 0.208633 -0.013587 0.943635 0.256596\n7402 31.636071 -0.033999 -0.968400 1.338937 0.197737 -0.017014 0.950081 0.240741\n7403 31.645671 -0.034947 -0.968673 1.338671 0.188056 -0.019881 0.955543 0.226224\n7404 31.653119 -0.036198 -0.968178 1.338412 0.177246 -0.021643 0.960763 0.212251\n7405 31.662168 -0.037082 -0.968953 1.338177 0.167053 -0.024904 0.965127 0.200006\n7406 31.671314 -0.037898 -0.969321 1.337960 0.155313 -0.028379 0.969685 0.186502\n7407 31.677887 -0.039346 -0.969664 1.337814 0.143934 -0.031595 0.973586 0.174398\n7408 31.685769 -0.039829 -0.970024 1.337540 0.135309 -0.036039 0.976732 0.162443\n7409 31.695468 -0.041471 -0.970770 1.337056 0.126832 -0.038613 0.979795 0.149746\n7410 31.703449 -0.042175 -0.970984 1.336797 0.118605 -0.041596 0.982370 0.138391\n7411 31.712251 -0.043583 -0.971589 1.336437 0.109562 -0.043537 0.984963 0.126291\n7412 31.721185 -0.044731 -0.971875 1.336234 0.098477 -0.045483 0.987351 0.115639\n7413 31.728150 -0.046054 -0.972294 1.335929 0.088427 -0.046925 0.989467 0.104566\n7414 31.737823 -0.046758 -0.972462 1.335490 0.083413 -0.049516 0.990911 0.093200\n7415 31.745515 -0.047821 -0.973332 1.335167 0.074270 -0.051001 0.992427 0.083497\n7416 31.753090 -0.048873 -0.973525 1.334958 0.063523 -0.053274 0.993811 0.073929\n7417 31.761753 -0.050322 -0.973744 1.334565 0.052730 -0.055459 0.994922 0.065384\n7418 31.771438 -0.050815 -0.974352 1.334299 0.045098 -0.059577 0.995579 0.056913\n7419 31.778717 -0.051470 -0.974657 1.334023 0.038435 -0.064013 0.996011 0.048857\n7420 31.787717 -0.052692 -0.975013 1.333628 0.028506 -0.067071 0.996502 0.040887\n7421 31.794859 -0.053432 -0.975296 1.333368 0.022026 -0.070663 0.996684 0.033801\n7422 31.802399 -0.053845 -0.975362 1.333224 0.019268 -0.075013 0.996620 0.027407\n7423 31.810952 -0.055279 -0.975693 1.332840 0.007692 -0.075434 0.996938 0.019089\n7424 31.819861 -0.056331 -0.975586 1.332613 0.001909 -0.076891 0.996971 0.011517\n7425 31.828879 -0.057285 -0.975626 1.332504 -0.003697 -0.078160 0.996924 0.004484\n7426 31.835795 -0.058395 -0.975804 1.332301 -0.011145 -0.078289 0.996864 -0.003093\n7427 31.845431 -0.059473 -0.975846 1.332096 -0.017387 -0.078078 0.996741 -0.010479\n7428 31.853587 -0.060416 -0.975714 1.332051 -0.022199 -0.077994 0.996549 -0.017713\n7429 31.862294 -0.061614 -0.975634 1.331850 -0.029170 -0.077104 0.996281 -0.025077\n7430 31.870941 -0.062517 -0.975779 1.331748 -0.034862 -0.075907 0.995984 -0.032235\n7431 31.878753 -0.062953 -0.975638 1.332019 -0.035791 -0.076045 0.995712 -0.038652\n7432 31.885719 -0.064685 -0.974175 1.331712 -0.044027 -0.075917 0.995116 -0.045192\n7433 31.895704 -0.065091 -0.975633 1.331490 -0.047624 -0.075670 0.994595 -0.052800\n7434 31.903277 -0.066807 -0.975363 1.331141 -0.058100 -0.075629 0.993691 -0.059016\n7435 31.912296 -0.067499 -0.976058 1.331028 -0.058990 -0.077911 0.993137 -0.064263\n7436 31.921264 -0.068882 -0.975457 1.330741 -0.066611 -0.078804 0.992169 -0.070379\n7437 31.928430 -0.069304 -0.975822 1.330353 -0.066816 -0.081726 0.991512 -0.075897\n7438 31.937069 -0.070663 -0.974776 1.330607 -0.071107 -0.083503 0.991006 -0.076666\n7439 31.945375 -0.071815 -0.975436 1.330283 -0.076589 -0.084991 0.990414 -0.077401\n7440 31.952540 -0.073175 -0.974888 1.330158 -0.082438 -0.086361 0.989834 -0.077297\n7441 31.961451 -0.073871 -0.974222 1.330295 -0.081788 -0.089127 0.989823 -0.074946\n7442 31.970024 -0.074777 -0.974029 1.330062 -0.085251 -0.089954 0.989755 -0.070896\n7443 31.979048 -0.074848 -0.973235 1.330375 -0.081770 -0.093587 0.990052 -0.065976\n7444 31.987098 -0.075797 -0.972578 1.330432 -0.082926 -0.095347 0.990137 -0.060512\n7445 31.995069 -0.075926 -0.972190 1.330369 -0.079485 -0.098413 0.990572 -0.052574\n7446 32.003045 -0.076783 -0.971658 1.330482 -0.083080 -0.097502 0.990828 -0.043023\n7447 32.012780 -0.076701 -0.970700 1.330921 -0.077920 -0.098939 0.991427 -0.034805\n7448 32.020238 -0.076816 -0.970151 1.331091 -0.076193 -0.098909 0.991868 -0.024686\n7449 32.027413 -0.076743 -0.969430 1.331311 -0.072023 -0.098203 0.992476 -0.012684\n7450 32.036172 -0.076534 -0.968420 1.331782 -0.067902 -0.096856 0.992978 -0.001511\n7451 32.045336 -0.076671 -0.967436 1.331969 -0.065592 -0.094028 0.993340 0.011498\n7452 32.052777 -0.076100 -0.966682 1.332490 -0.060353 -0.092217 0.993650 0.022657\n7453 32.062084 -0.075851 -0.965765 1.332690 -0.058110 -0.089147 0.993669 0.036042\n7454 32.069635 -0.075310 -0.964409 1.333300 -0.051677 -0.086983 0.993595 0.050322\n7455 32.079276 -0.073737 -0.963990 1.333868 -0.043374 -0.085753 0.993270 0.064653\n7456 32.086073 -0.073610 -0.962281 1.334417 -0.040306 -0.082185 0.992640 0.079289\n7457 32.095406 -0.072471 -0.961060 1.335005 -0.033528 -0.079698 0.991753 0.094602\n7458 32.104633 -0.071456 -0.959616 1.335635 -0.027671 -0.077309 0.990372 0.111448\n7459 32.111546 -0.070610 -0.957649 1.336171 -0.022411 -0.072519 0.988835 0.128237\n7460 32.120814 -0.069113 -0.956591 1.336704 -0.012321 -0.070304 0.986733 0.145817\n7461 32.128011 -0.067764 -0.955667 1.337137 -0.006116 -0.066197 0.984095 0.164738\n7462 32.135979 -0.066543 -0.953668 1.337793 0.001048 -0.062943 0.981140 0.182759\n7463 32.145894 -0.065775 -0.952617 1.338322 0.004909 -0.057968 0.977834 0.201138\n7464 32.153328 -0.064465 -0.951286 1.338828 0.011964 -0.055184 0.973887 0.219900\n7465 32.162097 -0.063144 -0.949778 1.339271 0.018291 -0.051273 0.969405 0.239356\n7466 32.170772 -0.061650 -0.948842 1.339709 0.026216 -0.050176 0.963939 0.260032\n7467 32.178922 -0.060186 -0.947843 1.340135 0.034979 -0.049070 0.958345 0.279184\n7468 32.186160 -0.059366 -0.946632 1.340732 0.036800 -0.044808 0.952322 0.299535\n7469 32.196300 -0.058199 -0.944875 1.341316 0.042887 -0.043149 0.945641 0.319472\n7470 32.203504 -0.056225 -0.944092 1.342036 0.052650 -0.040567 0.938335 0.339280\n7471 32.211949 -0.054917 -0.942816 1.342637 0.057710 -0.037037 0.930932 0.358698\n7472 32.220737 -0.053634 -0.941217 1.343243 0.060749 -0.032499 0.923167 0.378174\n7473 32.229001 -0.052837 -0.939899 1.344095 0.063934 -0.029416 0.914770 0.397798\n7474 32.237488 -0.052127 -0.939143 1.344211 0.070178 -0.024712 0.907113 0.414258\n7475 32.245616 -0.051019 -0.937136 1.345552 0.072998 -0.018706 0.898753 0.431931\n7476 32.252607 -0.049734 -0.935752 1.346435 0.077960 -0.014538 0.889958 0.449094\n7477 32.261387 -0.049201 -0.934228 1.347313 0.081868 -0.008390 0.881321 0.465296\n7478 32.270829 -0.048798 -0.933315 1.348269 0.086679 -0.003686 0.872380 0.481067\n7479 32.279136 -0.048287 -0.931947 1.349293 0.088817 0.002902 0.863362 0.496698\n7480 32.287768 -0.047585 -0.930962 1.350101 0.091853 0.006897 0.854465 0.511278\n7481 32.294774 -0.047174 -0.929874 1.351020 0.095826 0.010858 0.844617 0.526613\n7482 32.302744 -0.046476 -0.929230 1.351773 0.099857 0.012999 0.834686 0.541442\n7483 32.311508 -0.046096 -0.928385 1.352611 0.103488 0.015713 0.824711 0.555784\n7484 32.319784 -0.045568 -0.927712 1.353509 0.107527 0.018228 0.814232 0.570203\n7485 32.328920 -0.045300 -0.927373 1.354152 0.109495 0.020836 0.804084 0.583974\n7486 32.335972 -0.044596 -0.926762 1.354743 0.114217 0.022130 0.794617 0.595860\n7487 32.345219 -0.044724 -0.926786 1.355282 0.117625 0.024531 0.784512 0.608361\n7488 32.353798 -0.044337 -0.926741 1.355880 0.119506 0.028443 0.775129 0.619745\n7489 32.363817 -0.043796 -0.927333 1.356375 0.124859 0.027312 0.765535 0.630572\n7490 32.369538 -0.043555 -0.927401 1.356997 0.127550 0.031455 0.756350 0.640841\n7491 32.377490 -0.043229 -0.927650 1.357552 0.130425 0.033551 0.747091 0.650936\n7492 32.387461 -0.042220 -0.927589 1.358014 0.134808 0.037671 0.738486 0.659581\n7493 32.395785 -0.041480 -0.927597 1.358550 0.136225 0.044554 0.728888 0.669463\n7494 32.404355 -0.041293 -0.927590 1.358881 0.140068 0.048929 0.719479 0.678481\n7495 32.411657 -0.040659 -0.927415 1.359210 0.143342 0.054175 0.711490 0.685784\n7496 32.419413 -0.040480 -0.927612 1.359498 0.146746 0.057197 0.702476 0.694062\n7497 32.428861 -0.040520 -0.928080 1.359715 0.150199 0.057208 0.693726 0.702077\n7498 32.436602 -0.040399 -0.928132 1.359956 0.150801 0.062478 0.685208 0.709820\n7499 32.445840 -0.040464 -0.928581 1.360202 0.151770 0.064218 0.676610 0.717664\n7500 32.454417 -0.040704 -0.929471 1.360308 0.154792 0.061010 0.667867 0.725445\n7501 32.461370 -0.040462 -0.929952 1.360794 0.154838 0.064940 0.658936 0.733220\n7502 32.469556 -0.040933 -0.930891 1.361320 0.157444 0.063385 0.649213 0.741429\n7503 32.479383 -0.040241 -0.931554 1.361629 0.160615 0.066195 0.640896 0.747712\n7504 32.487014 -0.039815 -0.932298 1.361941 0.164376 0.069736 0.631408 0.754613\n7505 32.494938 -0.040252 -0.933247 1.362533 0.169197 0.069679 0.620335 0.762693\n7506 32.504698 -0.040256 -0.933878 1.362723 0.174678 0.072771 0.611125 0.768582\n7507 32.511810 -0.039939 -0.934320 1.362707 0.180481 0.077670 0.603545 0.772740\n7508 32.520975 -0.040115 -0.934981 1.362771 0.184683 0.080846 0.594454 0.778448\n7509 32.528672 -0.039941 -0.936927 1.362434 0.187639 0.078481 0.583472 0.786252\n7510 32.536546 -0.040540 -0.936617 1.362917 0.190701 0.082599 0.574372 0.791775\n7511 32.545241 -0.040790 -0.937520 1.362957 0.192780 0.082530 0.564639 0.798253\n7512 32.553496 -0.040982 -0.938723 1.362934 0.194616 0.082671 0.554508 0.804867\n7513 32.562016 -0.040537 -0.940249 1.362700 0.195799 0.085479 0.543050 0.812067\n7514 32.569356 -0.040383 -0.941850 1.362588 0.198940 0.084916 0.533391 0.817744\n7515 32.578774 -0.040148 -0.943515 1.362734 0.202725 0.082785 0.522371 0.824122\n7516 32.586980 -0.040626 -0.945197 1.362712 0.207815 0.079432 0.511173 0.830184\n7517 32.594549 -0.039575 -0.947586 1.362641 0.213760 0.081737 0.500324 0.835046\n7518 32.603454 -0.039357 -0.949850 1.362536 0.220602 0.081670 0.488090 0.840496\n7519 32.611903 -0.039516 -0.952160 1.362556 0.229096 0.078488 0.476157 0.845357\n7520 32.619393 -0.039871 -0.954471 1.362636 0.237502 0.073747 0.462383 0.851091\n7521 32.629253 -0.040134 -0.956811 1.362488 0.246649 0.071816 0.449905 0.855332\n7522 32.636736 -0.041185 -0.958845 1.362436 0.255155 0.064532 0.435556 0.860827\n7523 32.645763 -0.041114 -0.961552 1.362425 0.264203 0.063058 0.422140 0.864881\n7524 32.652867 -0.042031 -0.963589 1.362352 0.272730 0.056852 0.409478 0.868743\n7525 32.660761 -0.042988 -0.965844 1.362344 0.280131 0.050857 0.393841 0.873973\n7526 32.671566 -0.043629 -0.968669 1.361899 0.287022 0.044796 0.379097 0.878577\n7527 32.679106 -0.043871 -0.971079 1.361672 0.296077 0.041673 0.363951 0.882123\n7528 32.686016 -0.045348 -0.973136 1.361146 0.301696 0.033218 0.351076 0.885789\n7529 32.696863 -0.045542 -0.975594 1.361170 0.311366 0.028989 0.336107 0.888393\n7530 32.703313 -0.046270 -0.978169 1.360343 0.318810 0.023490 0.320989 0.891501\n7531 32.712039 -0.047285 -0.980123 1.359851 0.328451 0.017524 0.307602 0.892857\n7532 32.720399 -0.048440 -0.982449 1.359064 0.335089 0.009561 0.293578 0.895229\n7533 32.728797 -0.049824 -0.984972 1.358411 0.342319 0.000751 0.278897 0.897237\n7534 32.736304 -0.051101 -0.987999 1.357610 0.351769 -0.009568 0.261885 0.898656\n7535 32.745946 -0.052063 -0.990201 1.356694 0.359281 -0.015121 0.249737 0.899066\n7536 32.753496 -0.053609 -0.992553 1.355724 0.367570 -0.024286 0.234927 0.899506\n7537 32.762096 -0.054071 -0.995130 1.354387 0.377848 -0.030934 0.220004 0.898817\n7538 32.770426 -0.055078 -0.997481 1.353209 0.387873 -0.038645 0.206361 0.897484\n7539 32.778895 -0.055784 -0.999694 1.351903 0.397366 -0.046078 0.192461 0.896067\n7540 32.787345 -0.057028 -1.001694 1.350686 0.406511 -0.055366 0.178633 0.894301\n7541 32.795552 -0.057771 -1.003481 1.349460 0.415956 -0.062837 0.165455 0.891996\n7542 32.802956 -0.058793 -1.004810 1.348590 0.424877 -0.070743 0.151824 0.889620\n7543 32.812011 -0.059852 -1.006668 1.347025 0.431436 -0.076402 0.139393 0.888029\n7544 32.820343 -0.060660 -1.008204 1.345472 0.440030 -0.082408 0.126272 0.885233\n7545 32.828995 -0.061777 -1.009606 1.344168 0.447266 -0.089339 0.114434 0.882540\n7546 32.837336 -0.062431 -1.010523 1.343689 0.452887 -0.093674 0.101722 0.880779\n7547 32.845471 -0.063531 -1.011681 1.342529 0.457858 -0.098825 0.089021 0.879019\n7548 32.852922 -0.064112 -1.012932 1.341149 0.463956 -0.103888 0.077074 0.876363\n7549 32.862474 -0.065172 -1.013989 1.340067 0.468736 -0.110033 0.064886 0.874054\n7550 32.870913 -0.065568 -1.015239 1.338673 0.474555 -0.113399 0.054315 0.871199\n7551 32.878750 -0.066244 -1.016469 1.337376 0.479899 -0.117648 0.043111 0.868330\n7552 32.887111 -0.067075 -1.017208 1.336428 0.485991 -0.122924 0.032012 0.864684\n7553 32.895624 -0.067378 -1.019104 1.334674 0.492483 -0.126117 0.022622 0.860839\n7554 32.902861 -0.068014 -1.020531 1.333380 0.499690 -0.130965 0.013054 0.856147\n7555 32.912124 -0.068202 -1.021951 1.331715 0.506695 -0.136459 0.003554 0.851250\n7556 32.920362 -0.068674 -1.023383 1.330220 0.514480 -0.139925 -0.005875 0.845989\n7557 32.928798 -0.068685 -1.024745 1.328321 0.521372 -0.144875 -0.013802 0.840828\n7558 32.936511 -0.068977 -1.026222 1.327263 0.529113 -0.150362 -0.022253 0.834826\n7559 32.945123 -0.069265 -1.027606 1.325486 0.535347 -0.155873 -0.030372 0.829569\n7560 32.954362 -0.069031 -1.028703 1.324073 0.541689 -0.157358 -0.036330 0.824919\n7561 32.962311 -0.069352 -1.029268 1.322718 0.546971 -0.164504 -0.043785 0.819661\n7562 32.971224 -0.069264 -1.030478 1.321349 0.552370 -0.167939 -0.050671 0.814933\n7563 32.979245 -0.068977 -1.031250 1.320082 0.557105 -0.168700 -0.055015 0.811263\n7564 32.986818 -0.068928 -1.031862 1.318678 0.560896 -0.173317 -0.060483 0.807279\n7565 32.995458 -0.068601 -1.032460 1.317402 0.564287 -0.175438 -0.064500 0.804140\n7566 33.005803 -0.068205 -1.032553 1.316256 0.566963 -0.177883 -0.067153 0.801499\n7567 33.012210 -0.067328 -1.033174 1.315182 0.570378 -0.177414 -0.068680 0.799047\n7568 33.019438 -0.066259 -1.033315 1.314208 0.573062 -0.176283 -0.068491 0.797392\n7569 33.029245 -0.065287 -1.033394 1.313510 0.575288 -0.174766 -0.067368 0.796217\n7570 33.036537 -0.063872 -1.033212 1.312766 0.576759 -0.170561 -0.064412 0.796310\n7571 33.054340 -0.060983 -1.032619 1.311805 0.577360 -0.163919 -0.055252 0.797956\n7572 33.054359 -0.060983 -1.032619 1.311805 0.577360 -0.163919 -0.055252 0.797956\n7573 33.062055 -0.059693 -1.032245 1.311213 0.576170 -0.161278 -0.048714 0.799778\n7574 33.069930 -0.058098 -1.031610 1.310812 0.574332 -0.157798 -0.041455 0.802199\n7575 33.078335 -0.056551 -1.031311 1.310405 0.572371 -0.153578 -0.032494 0.804829\n7576 33.087505 -0.055223 -1.030846 1.310177 0.570262 -0.149948 -0.022987 0.807334\n7577 33.095793 -0.053345 -1.030227 1.309798 0.568931 -0.145968 -0.012862 0.809226\n7578 33.105233 -0.051532 -1.029527 1.309459 0.567975 -0.144924 -0.002249 0.810183\n7579 33.110732 -0.049901 -1.028759 1.308616 0.566585 -0.142562 0.008596 0.811531\n7580 33.121263 -0.048349 -1.028285 1.308401 0.565536 -0.138359 0.020474 0.812777\n7581 33.128921 -0.046948 -1.027369 1.308549 0.564223 -0.134804 0.032191 0.813907\n7582 33.137087 -0.044865 -1.026693 1.308191 0.563563 -0.131329 0.045724 0.814285\n7583 33.144931 -0.043238 -1.025578 1.308131 0.561817 -0.128787 0.057795 0.815129\n7584 33.153488 -0.041203 -1.024780 1.307930 0.561380 -0.125229 0.071845 0.814867\n7585 33.161925 -0.039735 -1.023765 1.307918 0.560206 -0.123117 0.084980 0.814733\n7586 33.170332 -0.037563 -1.022679 1.307932 0.560250 -0.120248 0.098796 0.813572\n7587 33.178932 -0.035828 -1.021317 1.308141 0.559372 -0.116913 0.112253 0.812917\n7588 33.187485 -0.034009 -1.020752 1.307779 0.559361 -0.114943 0.125793 0.811221\n7589 33.195343 -0.032182 -1.019732 1.307981 0.559930 -0.115003 0.137603 0.808900\n7590 33.204209 -0.030397 -1.018736 1.308152 0.561318 -0.114581 0.149918 0.805803\n7591 33.212140 -0.029032 -1.018174 1.307809 0.561889 -0.116626 0.160589 0.803051\n7592 33.219449 -0.027451 -1.017558 1.307740 0.564599 -0.117896 0.170988 0.798807\n7593 33.228773 -0.025671 -1.016966 1.307536 0.568517 -0.120863 0.180159 0.793551\n7594 33.237114 -0.024308 -1.016312 1.307238 0.573652 -0.125774 0.188524 0.787124\n7595 33.246068 -0.022658 -1.016254 1.306913 0.581211 -0.130418 0.196201 0.778903\n7596 33.254057 -0.021055 -1.016063 1.306392 0.589139 -0.134553 0.203753 0.770257\n7597 33.261990 -0.018917 -1.015504 1.306391 0.600082 -0.138508 0.211325 0.758986\n7598 33.269713 -0.017443 -1.015464 1.305262 0.606560 -0.143719 0.218218 0.750873\n7599 33.278259 -0.015283 -1.015203 1.305030 0.615240 -0.144750 0.226201 0.741189\n7600 33.286960 -0.013909 -1.015022 1.304039 0.622424 -0.150294 0.232421 0.732107\n7601 33.295266 -0.012140 -1.014626 1.303165 0.629826 -0.154511 0.239122 0.722680\n7602 33.303408 -0.010176 -1.014477 1.302477 0.635695 -0.155093 0.247484 0.714555\n7603 33.312051 -0.008674 -1.014028 1.301568 0.640824 -0.156748 0.254873 0.706975\n7604 33.320331 -0.006815 -1.013704 1.301416 0.645697 -0.159797 0.263661 0.698587\n7605 33.329020 -0.004605 -1.013777 1.300476 0.650871 -0.159462 0.272610 0.690379\n7606 33.337693 -0.001889 -1.012875 1.299721 0.654123 -0.155393 0.287046 0.682335\n7607 33.345367 -0.000212 -1.012407 1.300073 0.657000 -0.156440 0.295878 0.675525\n7608 33.352614 0.001642 -1.011804 1.299276 0.661841 -0.156567 0.304405 0.666926\n7609 33.362965 0.003979 -1.010919 1.299269 0.664589 -0.153343 0.316784 0.659132\n7610 33.371150 0.006032 -1.009854 1.299790 0.667627 -0.147352 0.330229 0.650777\n7611 33.378743 0.007876 -1.008781 1.299362 0.668975 -0.144482 0.343716 0.643006\n7612 33.388865 0.010343 -1.007815 1.299907 0.671722 -0.137238 0.357152 0.634348\n7613 33.396341 0.011898 -1.007578 1.300152 0.672982 -0.131687 0.370194 0.626666\n7614 33.405224 0.014641 -1.005801 1.299819 0.673616 -0.123412 0.385218 0.618561\n7615 33.411888 0.016152 -1.005139 1.301145 0.677021 -0.117391 0.396184 0.609016\n7616 33.421052 0.018872 -1.003824 1.301483 0.676102 -0.108721 0.413303 0.600206\n7617 33.427931 0.020097 -1.003349 1.302092 0.677022 -0.105389 0.423856 0.592351\n7618 33.436180 0.022623 -1.002280 1.302151 0.676308 -0.099486 0.438383 0.583550\n7619 33.446367 0.024403 -1.001755 1.302214 0.676095 -0.095724 0.451057 0.574700\n7620 33.454679 0.026286 -1.001197 1.302474 0.674912 -0.092593 0.464380 0.565926\n7621 33.462117 0.027830 -1.000877 1.302124 0.674785 -0.090401 0.477920 0.555054\n7622 33.469831 0.030236 -1.000198 1.302705 0.674165 -0.087916 0.491285 0.544436\n7623 33.479006 0.031854 -1.000521 1.302631 0.674679 -0.087904 0.502975 0.533008\n7624 33.487185 0.034055 -1.000471 1.302154 0.674218 -0.085522 0.516874 0.520536\n7625 33.494971 0.036286 -1.000499 1.302315 0.676298 -0.086827 0.528909 0.505309\n7626 33.502636 0.038041 -1.001069 1.301875 -0.676922 0.084568 -0.541713 -0.491093\n7627 33.512587 0.040804 -1.000512 1.301377 -0.677148 0.083652 -0.554326 -0.476650\n7628 33.520448 0.042728 -1.001089 1.301172 -0.678950 0.082578 -0.566099 -0.460152\n7629 33.527615 0.045689 -1.000822 1.300973 -0.678440 0.081590 -0.579917 -0.443575\n7630 33.536821 0.047897 -1.000924 1.300853 -0.678891 0.079758 -0.591932 -0.427039\n7631 33.544564 0.049527 -1.000637 1.300817 -0.677861 0.075466 -0.604941 -0.410920\n7632 33.552708 0.051842 -1.001085 1.300941 -0.675606 0.074955 -0.617111 -0.396375\n7633 33.562712 0.053664 -1.000953 1.301126 -0.672513 0.072744 -0.629497 -0.382320\n7634 33.571114 0.055627 -1.001075 1.301069 -0.668406 0.070813 -0.641618 -0.369522\n7635 33.579572 0.057081 -1.000859 1.301558 -0.664903 0.067000 -0.653167 -0.356072\n7636 33.588291 0.059312 -1.000659 1.301944 0.660015 -0.064429 0.664589 0.344312\n7637 33.595834 0.061098 -1.000809 1.302522 0.654316 -0.062350 0.676448 0.332267\n7638 33.602702 0.063022 -1.000799 1.303084 0.649025 -0.058374 0.687352 0.320790\n7639 33.611393 0.064662 -1.000706 1.303327 0.643767 -0.055926 0.697900 0.308824\n7640 33.619526 0.066581 -1.000771 1.304012 0.637781 -0.050468 0.708741 0.297279\n7641 33.629815 0.068168 -1.000835 1.304390 0.632280 -0.045738 0.718946 0.285040\n7642 33.637127 0.069882 -1.001053 1.304307 0.626594 -0.041574 0.728466 0.273843\n7643 33.645577 0.071821 -1.001180 1.304969 0.621215 -0.036027 0.738141 0.260657\n7644 33.652632 0.072950 -1.001544 1.304444 0.615222 -0.033141 0.747113 0.249453\n7645 33.662219 0.074813 -1.001930 1.304397 0.609327 -0.030626 0.755379 0.239135\n7646 33.670890 0.076208 -1.002192 1.304114 0.604662 -0.026695 0.763230 0.226167\n7647 33.679078 0.077428 -1.002813 1.304249 0.595159 -0.022938 0.773657 0.216134\n7648 33.686271 0.079598 -1.003377 1.303823 0.596306 -0.021161 0.777690 0.197916\n7649 33.696328 0.080577 -1.003349 1.303240 0.587763 -0.018235 0.786503 0.188720\n7650 33.704632 0.081843 -1.003374 1.303427 0.581614 -0.015078 0.793258 0.179554\n7651 33.712312 0.082753 -1.004064 1.303657 0.575853 -0.012948 0.799498 0.170379\n7652 33.719844 0.083784 -1.003564 1.303360 0.570888 -0.012579 0.805032 0.160786\n7653 33.728074 0.085687 -1.003161 1.302892 0.564632 -0.010001 0.811027 0.152730\n7654 33.737519 0.086458 -1.003909 1.303641 0.557065 -0.005424 0.818480 0.140498\n7655 33.745908 0.087437 -1.004309 1.303707 0.552746 -0.001350 0.823328 0.128841\n7656 33.752894 0.088256 -1.003229 1.304357 0.544868 0.003168 0.830116 0.118392\n7657 33.760747 0.089785 -1.003610 1.304224 0.539726 0.008410 0.834802 0.108309\n7658 33.772089 0.090614 -1.003216 1.304553 0.531579 0.013865 0.841138 0.098583\n7659 33.777880 0.091681 -1.003025 1.304831 0.523931 0.018463 0.846918 0.088799\n7660 33.785917 0.092378 -1.002181 1.305293 0.516535 0.023120 0.852530 0.076487\n7661 33.797429 0.093669 -1.002543 1.305485 0.513627 0.028870 0.854952 0.066415\n7662 33.803863 0.094333 -1.001339 1.306133 0.503532 0.032419 0.861388 0.058441\n7663 33.811551 0.094842 -1.001081 1.306442 0.498448 0.036702 0.864787 0.048440\n7664 33.820434 0.095553 -1.001098 1.306675 0.492673 0.040697 0.868356 0.039682\n7665 33.828420 0.095927 -1.000079 1.307400 0.483935 0.042836 0.873571 0.029071\n7666 33.836718 0.096520 -0.999750 1.307678 0.476617 0.046499 0.877641 0.020518\n7667 33.845828 0.096519 -0.998527 1.308329 0.466771 0.048927 0.882980 0.008788\n7668 33.853568 0.097194 -0.998771 1.308762 0.460400 0.051640 0.886207 0.001658\n7669 33.862101 0.097404 -0.997620 1.309559 0.449746 0.054865 0.891409 -0.010405\n7670 33.869819 0.097981 -0.996892 1.309990 0.441958 0.057546 0.894935 -0.021290\n7671 33.878060 0.097328 -0.996150 1.310944 0.430076 0.060578 0.900170 -0.032547\n7672 33.887505 0.098904 -0.995698 1.310666 0.422793 0.063576 0.902893 -0.044590\n7673 33.895805 0.098819 -0.994830 1.311589 0.413484 0.067934 0.906154 -0.057459\n7674 33.902877 0.099118 -0.994267 1.312107 0.403951 0.071371 0.909276 -0.070330\n7675 33.910763 0.099337 -0.993573 1.312621 0.396771 0.076515 0.910870 -0.083872\n7676 33.922505 0.098863 -0.992927 1.313343 0.387980 0.080800 0.912972 -0.097081\n7677 33.928701 0.099885 -0.992219 1.313980 0.383347 0.085695 0.912775 -0.111993\n7678 33.937367 0.100466 -0.991344 1.314076 0.375852 0.090028 0.913804 -0.124869\n7679 33.945764 0.100539 -0.990821 1.314740 0.368298 0.091851 0.914794 -0.138101\n7680 33.952870 0.101065 -0.989897 1.314426 0.366377 0.095541 0.912775 -0.153237\n7681 33.962522 0.101904 -0.988726 1.315650 0.362193 0.103898 0.911760 -0.163450\n7682 33.970506 0.101699 -0.988527 1.316250 0.353597 0.105015 0.912563 -0.176551\n7683 33.978587 0.102239 -0.988358 1.316431 0.353340 0.107364 0.910306 -0.186995\n7684 33.987489 0.102624 -0.987850 1.316679 0.352557 0.108608 0.908088 -0.198203\n7685 33.995481 0.103162 -0.986725 1.317299 0.350668 0.112446 0.906163 -0.207982\n7686 34.004433 0.103955 -0.986128 1.317517 0.351326 0.114654 0.903843 -0.215620\n7687 34.011590 0.105011 -0.985294 1.317473 0.352393 0.117580 0.901453 -0.222210\n7688 34.020360 0.105167 -0.985262 1.318152 0.353537 0.118689 0.898925 -0.229909\n7689 34.028146 0.105973 -0.984886 1.318133 0.354423 0.119234 0.897476 -0.233892\n7690 34.037582 0.106969 -0.983845 1.318751 0.355571 0.123764 0.894478 -0.241166\n7691 34.045789 0.107977 -0.982783 1.319092 0.356572 0.126924 0.892529 -0.245232\n7692 34.053695 0.108905 -0.981794 1.319315 0.356739 0.130201 0.891040 -0.248660\n7693 34.060731 0.109739 -0.980529 1.319751 0.357688 0.133882 0.889302 -0.251550\n7694 34.069970 0.110878 -0.979438 1.320189 0.356250 0.138631 0.887981 -0.255651\n7695 34.078408 0.111759 -0.978217 1.320513 0.357280 0.141374 0.886501 -0.257840\n7696 34.086078 0.112738 -0.977226 1.320948 0.357701 0.144433 0.885367 -0.259449\n7697 34.095524 0.113790 -0.976343 1.320845 0.359192 0.144769 0.884796 -0.259152\n7698 34.104784 0.114934 -0.975220 1.321701 0.358222 0.148144 0.884507 -0.259572\n7699 34.112254 0.115408 -0.974599 1.321910 0.360475 0.150685 0.883512 -0.258375\n7700 34.119394 0.116512 -0.973773 1.322192 0.361607 0.149161 0.883787 -0.256731\n7701 34.128340 0.117785 -0.973256 1.322374 0.363266 0.149763 0.883509 -0.254992\n7702 34.136399 0.118360 -0.972638 1.323182 0.363842 0.150480 0.883773 -0.252824\n7703 34.145345 0.119534 -0.971766 1.323529 0.365804 0.148755 0.884267 -0.249262\n7704 34.154205 0.120337 -0.971017 1.324001 0.368059 0.147890 0.884660 -0.245025\n7705 34.162062 0.121155 -0.970807 1.324317 0.371109 0.144876 0.885363 -0.239628\n7706 34.169110 0.121878 -0.970205 1.324880 0.374218 0.144473 0.885538 -0.234330\n7707 34.178260 0.122589 -0.969561 1.325464 0.374406 0.141564 0.887453 -0.228488\n7708 34.187446 0.123230 -0.968913 1.325774 0.379693 0.139777 0.887350 -0.221146\n7709 34.195116 0.124370 -0.969214 1.325802 0.383520 0.137111 0.887523 -0.215442\n7710 34.202930 0.124428 -0.968050 1.327143 0.386938 0.136613 0.887901 -0.207960\n7711 34.210735 0.125856 -0.967655 1.327487 0.392262 0.135491 0.887207 -0.201584\n7712 34.221865 0.125366 -0.966701 1.328443 0.393866 0.133627 0.889397 -0.189702\n7713 34.228133 0.126054 -0.966522 1.329296 0.396824 0.131474 0.889886 -0.182616\n7714 34.237155 0.126177 -0.966157 1.330438 0.400959 0.129131 0.890250 -0.173241\n7715 34.245399 0.127430 -0.966103 1.330568 0.406203 0.126567 0.890017 -0.163857\n7716 34.252761 0.127437 -0.965708 1.331333 0.408359 0.124017 0.891438 -0.152320\n7717 34.262274 0.127658 -0.965206 1.331727 0.410680 0.121538 0.892635 -0.140619\n7718 34.269229 0.128373 -0.965663 1.332221 0.416555 0.120223 0.891817 -0.129195\n7719 34.278325 0.129088 -0.964356 1.332843 0.419329 0.116410 0.892314 -0.119952\n7720 34.286166 0.128763 -0.964145 1.333712 0.421159 0.114326 0.893101 -0.109201\n7721 34.295973 0.129625 -0.964321 1.333961 0.426444 0.111539 0.892241 -0.098032\n7722 34.304020 0.129730 -0.964275 1.334299 0.429695 0.109690 0.892157 -0.085941\n7723 34.313068 0.129822 -0.964748 1.335048 0.435966 0.108277 0.890341 -0.074178\n7724 34.320251 0.130146 -0.964038 1.335650 0.440112 0.107813 0.889186 -0.063454\n7725 34.327376 0.129998 -0.964100 1.336280 0.443390 0.106040 0.888475 -0.052658\n7726 34.336267 0.130402 -0.964219 1.336490 0.448638 0.102460 0.886926 -0.039860\n7727 34.344750 0.130748 -0.964556 1.336545 0.453886 0.098349 0.885247 -0.025563\n7728 34.354099 0.130670 -0.964971 1.337269 0.456791 0.094507 0.884440 -0.013297\n7729 34.362605 0.131056 -0.965124 1.337781 0.461297 0.090379 0.882630 -0.001371\n7730 34.370610 0.131103 -0.965495 1.338522 0.460989 0.085694 0.883157 0.013376\n7731 34.379044 0.131045 -0.965484 1.338917 0.464912 0.081142 0.881209 0.027275\n7732 34.387013 0.130950 -0.965685 1.339800 0.465087 0.076762 0.880940 0.041778\n7733 34.394688 0.130773 -0.965756 1.340301 0.467404 0.071922 0.879336 0.055946\n7734 34.404521 0.130498 -0.965595 1.340660 0.471235 0.067106 0.876678 0.069795\n7735 34.411992 0.129768 -0.966020 1.341054 0.471816 0.061730 0.875371 0.085469\n7736 34.420554 0.129593 -0.966063 1.341545 0.472385 0.055890 0.873824 0.100798\n7737 34.428339 0.129168 -0.966560 1.342091 0.474374 0.049721 0.870846 0.118849\n7738 34.436144 0.128223 -0.966560 1.342715 0.474918 0.043239 0.868797 0.133325\n7739 34.445262 0.128644 -0.966415 1.342556 0.478077 0.035838 0.864679 0.149959\n7740 34.454480 0.128746 -0.966600 1.342378 0.480926 0.029156 0.860156 0.167308\n7741 34.463055 0.128479 -0.966653 1.342883 0.483822 0.023309 0.854830 0.186112\n7742 34.469836 0.128399 -0.967809 1.343600 0.487668 0.017284 0.848974 0.202791\n7743 34.477435 0.128013 -0.966936 1.343406 0.489431 0.010852 0.843452 0.221197\n7744 34.485865 0.127873 -0.967546 1.343195 0.491485 0.005048 0.836608 0.241875\n7745 34.494844 0.128080 -0.967915 1.343251 0.496681 -0.001808 0.827662 0.261306\n7746 34.504019 0.127719 -0.968357 1.343264 0.498728 -0.008684 0.820228 0.280038\n7747 34.512141 0.127101 -0.968816 1.343201 0.500350 -0.016205 0.812431 0.298903\n7748 34.519722 0.126779 -0.969276 1.343172 0.501851 -0.022848 0.804475 0.316929\n7749 34.527414 0.126505 -0.969712 1.343168 0.503453 -0.029397 0.796092 0.334529\n7750 34.538318 0.126306 -0.970163 1.343019 0.505501 -0.035068 0.787169 0.351574\n7751 34.545255 0.126452 -0.970503 1.343310 0.507172 -0.041684 0.777727 0.369026\n7752 34.553629 0.126233 -0.970990 1.343037 0.509148 -0.046516 0.768653 0.384418\n7753 34.561874 0.126278 -0.971170 1.342622 0.512087 -0.051290 0.758812 0.399175\n7754 34.569798 0.126104 -0.971448 1.342510 0.514768 -0.055491 0.748947 0.413537\n7755 34.577337 0.125646 -0.971816 1.342582 0.516224 -0.059145 0.740140 0.426856\n7756 34.587845 0.125591 -0.971984 1.342503 0.519502 -0.063459 0.730031 0.439483\n7757 34.595354 0.125570 -0.972483 1.342664 0.521787 -0.065828 0.720825 0.451460\n7758 34.604042 0.124674 -0.972364 1.342029 0.521914 -0.070440 0.712216 0.464103\n7759 34.612409 0.124288 -0.972820 1.342160 0.521792 -0.074143 0.704068 0.475946\n7760 34.621491 0.124191 -0.973096 1.341922 0.523465 -0.078326 0.693780 0.488385\n7761 34.628490 0.123944 -0.972914 1.341713 0.523538 -0.082624 0.685277 0.499478\n7762 34.637808 0.123440 -0.973885 1.341398 0.521179 -0.087287 0.675576 0.514150\n7763 34.645330 0.123179 -0.972913 1.341337 0.524536 -0.089151 0.665379 0.523626\n7764 34.652679 0.122954 -0.973159 1.341284 0.524964 -0.093462 0.654991 0.535411\n7765 34.662059 0.122859 -0.973034 1.341019 0.526494 -0.095617 0.643718 0.547072\n7766 34.671005 0.122620 -0.972830 1.341190 0.527276 -0.098282 0.634779 0.556216\n7767 34.678656 0.122115 -0.973272 1.341196 0.528054 -0.102427 0.624167 0.566642\n7768 34.688677 0.123057 -0.971714 1.340972 0.531204 -0.101022 0.613151 0.575902\n7769 34.695173 0.121927 -0.972778 1.341307 0.531506 -0.105062 0.604877 0.583599\n7770 34.704468 0.121062 -0.973082 1.340974 0.534505 -0.109609 0.593477 0.591671\n7771 34.711963 0.121356 -0.972333 1.341248 0.535981 -0.111753 0.583727 0.599581\n7772 34.720353 0.121275 -0.971861 1.341192 0.536433 -0.114362 0.573165 0.608805\n7773 34.729370 0.121155 -0.971171 1.341519 0.538296 -0.117809 0.561825 0.617017\n7774 34.737984 0.121600 -0.970140 1.341833 0.538497 -0.119916 0.551305 0.625863\n7775 34.745258 0.121492 -0.969337 1.342113 0.538877 -0.122801 0.539153 0.635488\n7776 34.753288 0.121127 -0.968451 1.342754 0.538200 -0.126418 0.526573 0.645817\n7777 34.762476 0.121344 -0.967463 1.343029 0.538450 -0.128794 0.514471 0.654831\n7778 34.770964 0.120439 -0.966316 1.343982 0.536690 -0.130760 0.500871 0.666329\n7779 34.778065 0.121036 -0.965279 1.344565 0.535561 -0.133631 0.487663 0.676389\n7780 34.788028 0.120745 -0.964137 1.345275 0.532829 -0.134865 0.475244 0.687057\n7781 34.795500 0.120464 -0.962756 1.346605 0.527264 -0.134249 0.464766 0.698543\n7782 34.803972 0.120275 -0.961551 1.347236 0.526682 -0.135961 0.451491 0.707302\n7783 34.812164 0.120298 -0.960207 1.348162 0.522493 -0.134752 0.439622 0.718036\n7784 34.819727 0.120103 -0.958616 1.349120 0.520662 -0.137244 0.426258 0.726897\n7785 34.828849 0.119572 -0.956720 1.350024 0.518577 -0.140042 0.414037 0.734874\n7786 34.838691 0.120077 -0.955729 1.350776 0.517318 -0.139977 0.400027 0.743483\n7787 34.845198 0.119966 -0.953436 1.351907 0.513198 -0.140383 0.387340 0.752920\n7788 34.853551 0.120464 -0.952028 1.352982 0.511377 -0.141150 0.373744 0.760845\n7789 34.860804 0.120148 -0.949879 1.354183 0.507691 -0.141822 0.358744 0.770350\n7790 34.870856 0.120011 -0.948059 1.355161 0.503402 -0.143716 0.343418 0.779741\n7791 34.878495 0.120505 -0.946900 1.356393 0.500613 -0.143726 0.328398 0.787962\n7792 34.887652 0.120972 -0.945323 1.357633 0.497159 -0.143045 0.313141 0.796438\n7793 34.895752 0.120531 -0.943767 1.358707 0.491516 -0.146054 0.294095 0.806591\n7794 34.904737 0.121093 -0.942270 1.359955 0.487524 -0.146112 0.276792 0.815082\n7795 34.911844 0.121039 -0.940650 1.360723 0.482405 -0.148972 0.257180 0.823985\n7796 34.920118 0.120838 -0.939289 1.362246 0.477371 -0.147549 0.236773 0.833238\n7797 34.928350 0.121165 -0.937790 1.363353 0.472678 -0.148005 0.217377 0.841081\n7798 34.935986 0.121213 -0.936458 1.364635 0.467943 -0.147591 0.197680 0.848628\n7799 34.945360 0.121372 -0.935222 1.365778 0.463414 -0.146903 0.177083 0.855750\n7800 34.953554 0.121520 -0.933985 1.366912 0.459029 -0.145811 0.156603 0.862269\n7801 34.960594 0.121600 -0.932779 1.368035 0.454588 -0.146129 0.135632 0.868101\n7802 34.971776 0.121897 -0.931851 1.369112 0.450197 -0.144975 0.115329 0.873501\n7803 34.978429 0.122031 -0.930752 1.370243 0.445399 -0.144931 0.094162 0.878492\n7804 34.986357 0.122557 -0.929831 1.371101 0.440678 -0.144035 0.073255 0.883001\n7805 34.995257 0.123014 -0.928430 1.372259 0.434820 -0.144496 0.051610 0.887349\n7806 35.004029 0.122992 -0.927850 1.373184 0.428656 -0.144334 0.030220 0.891352\n7807 35.012104 0.123067 -0.926597 1.374194 0.421357 -0.145980 0.007132 0.895041\n7808 35.020422 0.123425 -0.925385 1.375284 0.414037 -0.147551 -0.015525 0.898088\n7809 35.027547 0.123960 -0.924619 1.375952 0.405858 -0.147704 -0.038101 0.901117\n7810 35.038138 0.124337 -0.923578 1.376719 0.398016 -0.148245 -0.060203 0.903317\n7811 35.045183 0.124581 -0.922472 1.377921 0.390626 -0.147292 -0.081812 0.904999\n7812 35.055301 0.125203 -0.921446 1.378969 0.383074 -0.147217 -0.103202 0.906053\n7813 35.062233 0.125689 -0.920109 1.380022 0.376213 -0.149375 -0.123377 0.906052\n7814 35.069453 0.126487 -0.918718 1.380661 0.367025 -0.149092 -0.145369 0.906605\n7815 35.078848 0.127363 -0.917279 1.381214 0.357752 -0.151660 -0.165865 0.906367\n7816 35.088405 0.128270 -0.916321 1.382054 0.353203 -0.151503 -0.184100 0.904656\n7817 35.096333 0.129425 -0.915076 1.382677 0.346131 -0.150994 -0.201255 0.903820\n7818 35.104718 0.130771 -0.913572 1.383119 0.339153 -0.151181 -0.216852 0.902826\n7819 35.112151 0.131722 -0.912435 1.384052 0.332893 -0.150052 -0.232115 0.901548\n7820 35.120867 0.133008 -0.910949 1.384746 0.325647 -0.149406 -0.246381 0.900515\n7821 35.129009 0.134481 -0.909683 1.385351 0.318236 -0.147723 -0.260198 0.899556\n7822 35.136427 0.135869 -0.908142 1.385890 0.309574 -0.148563 -0.273326 0.898546\n7823 35.145408 0.137372 -0.907003 1.386262 0.301639 -0.148148 -0.285562 0.897508\n7824 35.153426 0.138977 -0.905234 1.386757 0.291919 -0.149022 -0.298926 0.896225\n7825 35.162036 0.140751 -0.904076 1.386992 0.283767 -0.148702 -0.309290 0.895379\n7826 35.169060 0.142705 -0.902431 1.387410 0.275060 -0.150164 -0.320737 0.893823\n7827 35.178403 0.144483 -0.900716 1.387671 0.266493 -0.148677 -0.329945 0.893316\n7828 35.187344 0.146397 -0.899258 1.387835 0.259670 -0.148474 -0.338618 0.892113\n7829 35.195351 0.148580 -0.898151 1.387967 0.255263 -0.147774 -0.344861 0.891109\n7830 35.202684 0.150221 -0.896982 1.388183 0.250073 -0.145922 -0.350431 0.890712\n7831 35.210739 0.152101 -0.895782 1.388568 0.245199 -0.145182 -0.355590 0.890143\n7832 35.221738 0.154197 -0.894673 1.388805 0.241631 -0.145252 -0.359824 0.889406\n7833 35.228928 0.156146 -0.893512 1.388725 0.236944 -0.144172 -0.363551 0.889327\n7834 35.237341 0.157967 -0.892529 1.389098 0.236147 -0.142574 -0.365269 0.889093\n7835 35.245675 0.159602 -0.892028 1.389143 0.235991 -0.139397 -0.366256 0.889232\n7836 35.252409 0.161653 -0.890919 1.389279 0.233784 -0.138628 -0.367905 0.889254\n7837 35.261959 0.163192 -0.890311 1.389145 0.233847 -0.138196 -0.366037 0.890075\n7838 35.270581 0.164735 -0.889225 1.389079 0.232882 -0.140498 -0.363613 0.890961\n7839 35.278834 0.166766 -0.888735 1.389088 0.234944 -0.139855 -0.360711 0.891701\n7840 35.286476 0.168402 -0.887478 1.389242 0.234942 -0.142371 -0.356458 0.893012\n7841 35.294096 0.169870 -0.887258 1.389169 0.239332 -0.142248 -0.349945 0.894441\n7842 35.305091 0.171698 -0.886171 1.389129 0.239782 -0.146651 -0.344497 0.895723\n7843 35.312159 0.173041 -0.885176 1.389047 0.240005 -0.151020 -0.339189 0.896962\n7844 35.322173 0.174664 -0.884532 1.389186 0.245567 -0.151835 -0.330189 0.898676\n7845 35.328860 0.175993 -0.883777 1.389412 0.249840 -0.153851 -0.322140 0.900075\n7846 35.336008 0.177242 -0.883174 1.389583 0.255022 -0.157427 -0.313335 0.901111\n7847 35.344112 0.178381 -0.882441 1.389905 0.261373 -0.160570 -0.304415 0.901794\n7848 35.353765 0.178970 -0.881773 1.390000 0.267491 -0.164617 -0.294629 0.902521\n7849 35.361802 0.179790 -0.881422 1.390149 0.275432 -0.168260 -0.283698 0.902963\n7850 35.370615 0.180450 -0.880959 1.390347 0.284200 -0.172824 -0.272732 0.902762\n7851 35.378851 0.180783 -0.880549 1.390582 0.293414 -0.178484 -0.261176 0.902130\n7852 35.385653 0.181314 -0.880228 1.390749 0.303392 -0.184048 -0.248726 0.901230\n7853 35.395909 0.181657 -0.879978 1.390808 0.313212 -0.190229 -0.236102 0.899982\n7854 35.403901 0.182053 -0.879805 1.390747 0.323899 -0.195737 -0.222623 0.898452\n7855 35.411798 0.182477 -0.879763 1.390765 0.334946 -0.201447 -0.208406 0.896547\n7856 35.421114 0.183447 -0.879654 1.390866 0.347934 -0.204337 -0.192757 0.894446\n7857 35.429534 0.183274 -0.879800 1.390782 0.358921 -0.211754 -0.177227 0.891586\n7858 35.437456 0.183653 -0.879646 1.390839 0.370944 -0.218469 -0.160703 0.888170\n7859 35.445423 0.183895 -0.879462 1.390925 0.383455 -0.222947 -0.143025 0.884760\n7860 35.454097 0.184073 -0.879390 1.391302 0.396807 -0.228731 -0.124006 0.880255\n7861 35.461234 0.184184 -0.879474 1.391219 0.409387 -0.233569 -0.105202 0.875660\n7862 35.471287 0.184067 -0.879728 1.391383 0.422741 -0.237823 -0.085021 0.870346\n7863 35.479281 0.183795 -0.879991 1.391599 0.435944 -0.243232 -0.066032 0.863962\n7864 35.487034 0.183379 -0.880329 1.391644 0.448163 -0.250486 -0.047033 0.856852\n7865 35.495203 0.183131 -0.880664 1.392028 0.461265 -0.258187 -0.028925 0.848374\n7866 35.502983 0.182592 -0.881132 1.392231 0.474098 -0.264136 -0.010048 0.839859\n7867 35.510679 0.182104 -0.881863 1.392039 0.484767 -0.269658 0.008123 0.831997\n7868 35.521695 0.181774 -0.882354 1.392118 0.496575 -0.274434 0.024151 0.823114\n7869 35.528085 0.180754 -0.883144 1.391532 0.507188 -0.283753 0.043567 0.812617\n7870 35.537204 0.180295 -0.883752 1.391887 0.518612 -0.290287 0.060441 0.801949\n7871 35.545611 0.179914 -0.884198 1.392335 0.529556 -0.296759 0.077604 0.790874\n7872 35.552492 0.179040 -0.885683 1.391929 0.538598 -0.301220 0.095206 0.781098\n7873 35.560525 0.178736 -0.886790 1.391936 0.549071 -0.303937 0.113586 0.770222\n7874 35.569575 0.178455 -0.887883 1.391842 0.558849 -0.307542 0.131214 0.758874\n7875 35.579359 0.178101 -0.888854 1.391909 0.567664 -0.311177 0.148354 0.747608\n7876 35.586314 0.178008 -0.889968 1.391985 0.577307 -0.314483 0.165634 0.735107\n7877 35.595188 0.177928 -0.891324 1.391988 0.585876 -0.314893 0.185441 0.723328\n7878 35.602215 0.177579 -0.892547 1.391977 0.594315 -0.318577 0.201479 0.710426\n7879 35.611142 0.177381 -0.894290 1.391276 0.600981 -0.321946 0.219155 0.697957\n7880 35.620567 0.177675 -0.895021 1.391229 0.611251 -0.322292 0.235061 0.683554\n7881 35.628701 0.178130 -0.896157 1.391235 0.621578 -0.324397 0.251464 0.667213\n7882 35.635680 0.178555 -0.897238 1.391707 0.629332 -0.324738 0.267996 0.653195\n7883 35.644126 0.178954 -0.898363 1.391492 0.637423 -0.324890 0.284577 0.638087\n7884 35.655328 0.179255 -0.899432 1.390648 0.646801 -0.324889 0.300090 0.621322\n7885 35.661152 0.179918 -0.900865 1.390430 0.655356 -0.324891 0.315146 0.604680\n7886 35.670366 0.180725 -0.901866 1.390377 0.662470 -0.324367 0.332987 0.587400\n7887 35.679056 0.181689 -0.902966 1.389863 0.668897 -0.321879 0.350177 0.571268\n7888 35.685596 0.182032 -0.904149 1.389368 0.676278 -0.322774 0.363031 0.553781\n7889 35.695983 0.182604 -0.905350 1.389160 0.680860 -0.321774 0.380666 0.536642\n7890 35.702984 0.183423 -0.906587 1.388649 0.685064 -0.322576 0.396096 0.519365\n7891 35.710506 0.184170 -0.907934 1.388627 0.688404 -0.322635 0.411324 0.502811\n7892 35.719580 0.184804 -0.909373 1.388531 -0.692242 0.323596 -0.425940 -0.484419\n7893 35.728633 0.185209 -0.911083 1.388338 -0.694831 0.324474 -0.439903 -0.467345\n7894 35.736833 0.186316 -0.912127 1.387569 -0.698691 0.323864 -0.454099 -0.448037\n7895 35.745536 0.187636 -0.913504 1.387679 -0.702696 0.324617 -0.466731 -0.427790\n7896 35.752246 0.188621 -0.915243 1.387109 -0.705765 0.323999 -0.478913 -0.409345\n7897 35.761360 0.189974 -0.916541 1.386620 -0.708053 0.322516 -0.493013 -0.389336\n7898 35.769047 0.191457 -0.917916 1.386114 -0.711530 0.321737 -0.504219 -0.368745\n7899 35.778801 0.193158 -0.919216 1.385859 -0.715436 0.318688 -0.517093 -0.345261\n7900 35.787014 0.194857 -0.920975 1.385257 -0.718125 0.315463 -0.529298 -0.323456\n7901 35.795235 0.196432 -0.922472 1.384590 -0.720856 0.310468 -0.542149 -0.300084\n7902 35.803875 0.198373 -0.923498 1.384520 -0.723226 0.306292 -0.554606 -0.274847\n7903 35.812865 0.200519 -0.924843 1.383717 -0.724136 0.301806 -0.567140 -0.250785\n7904 35.820111 0.202110 -0.925671 1.383066 -0.726662 0.294970 -0.577905 -0.225791\n7905 35.827925 0.204618 -0.926955 1.383350 -0.726285 0.288873 -0.589991 -0.202417\n7906 35.836722 0.205655 -0.927445 1.382871 -0.726109 0.280851 -0.602136 -0.176977\n7907 35.845108 0.207516 -0.927766 1.382822 -0.725297 0.274435 -0.612364 -0.153752\n7908 35.853861 0.209214 -0.928234 1.382210 -0.723700 0.266984 -0.623009 -0.129761\n7909 35.862186 0.210296 -0.928846 1.381792 -0.723485 0.260560 -0.630159 -0.107604\n7910 35.869531 0.211735 -0.929174 1.381489 -0.720227 0.252719 -0.640392 -0.085469\n7911 35.877332 0.213372 -0.929871 1.381378 -0.716382 0.247171 -0.649067 -0.066448\n7912 35.888094 0.214705 -0.930260 1.381096 -0.713175 0.240471 -0.656889 -0.045300\n7913 35.894872 0.216130 -0.930421 1.380367 -0.709845 0.234471 -0.663712 -0.025092\n7914 35.903881 0.217440 -0.930715 1.380489 -0.704603 0.225860 -0.672675 -0.005415\n7915 35.912569 0.218528 -0.931125 1.380396 -0.700648 0.218612 -0.679040 0.014367\n7916 35.919321 0.219852 -0.931388 1.380430 -0.693826 0.211406 -0.687593 0.033586\n7917 35.928453 0.220860 -0.931002 1.379680 0.687547 -0.203754 0.694946 -0.053048\n7918 35.936914 0.221957 -0.931714 1.379838 0.680270 -0.194741 0.702828 -0.073079\n7919 35.945923 0.223096 -0.931311 1.379397 0.675668 -0.186269 0.707205 -0.092939\n7920 35.953256 0.224186 -0.931430 1.379314 0.668260 -0.177539 0.713493 -0.113300\n7921 35.960709 0.225012 -0.931134 1.379142 0.658729 -0.169243 0.720675 -0.134388\n7922 35.969542 0.225972 -0.931023 1.378972 0.651176 -0.160509 0.725258 -0.155585\n7923 35.978291 0.226924 -0.930187 1.379079 0.644419 -0.152845 0.727868 -0.177682\n7924 35.986639 0.227759 -0.929696 1.379218 0.635173 -0.142005 0.733320 -0.196551\n7925 35.996203 0.228366 -0.929832 1.378942 0.629976 -0.133716 0.733551 -0.217147\n7926 36.003642 0.228934 -0.928866 1.379021 0.622081 -0.124254 0.735571 -0.237722\n7927 36.011719 0.229260 -0.928023 1.379551 0.614987 -0.114743 0.736349 -0.257711\n7928 36.018915 0.229685 -0.927348 1.379984 0.605435 -0.106091 0.738417 -0.277369\n7929 36.028098 0.229939 -0.926641 1.380351 0.596384 -0.097097 0.739305 -0.297198\n7930 36.037290 0.229838 -0.925901 1.380563 0.588334 -0.086955 0.738507 -0.317662\n7931 36.046134 0.229461 -0.924994 1.381155 0.579255 -0.077730 0.738007 -0.337295\n7932 36.052186 0.229009 -0.924563 1.381910 0.569967 -0.065964 0.736801 -0.357646\n7933 36.063710 0.228669 -0.923740 1.382325 0.558953 -0.056826 0.736786 -0.376151\n7934 36.070046 0.228196 -0.922992 1.382756 0.548308 -0.045863 0.736023 -0.394365\n7935 36.077227 0.227443 -0.921849 1.383175 0.538435 -0.035067 0.734627 -0.411316\n7936 36.085777 0.227055 -0.921704 1.383922 0.528360 -0.023457 0.732237 -0.429086\n7937 36.094935 0.226297 -0.920770 1.384514 0.517827 -0.012125 0.731363 -0.443641\n7938 36.102938 0.225644 -0.920372 1.384902 0.506840 -0.003220 0.731434 -0.456188\n7939 36.112641 0.224870 -0.919547 1.385370 0.497081 0.006758 0.729795 -0.469323\n7940 36.120014 0.223994 -0.918751 1.385970 0.486223 0.014158 0.729831 -0.480348\n7941 36.128728 0.223384 -0.918025 1.386553 0.476947 0.023796 0.728774 -0.490759\n7942 36.135909 0.222542 -0.917055 1.387529 0.467858 0.033825 0.728419 -0.499370\n7943 36.144770 0.221360 -0.916762 1.387760 -0.457780 -0.039428 -0.729501 0.506668\n7944 36.152283 0.220690 -0.916189 1.388151 -0.450734 -0.047667 -0.728496 0.513674\n7945 36.161041 0.219672 -0.915614 1.388678 -0.443874 -0.054748 -0.728041 0.519554\n7946 36.171189 0.218658 -0.914671 1.389093 -0.437689 -0.060732 -0.727532 0.524821\n7947 36.178075 0.217724 -0.914305 1.389630 -0.432047 -0.066790 -0.726840 0.529695\n7948 36.186383 0.216638 -0.913755 1.389897 -0.425720 -0.072212 -0.726792 0.534155\n7949 36.195555 0.216292 -0.913150 1.389658 -0.422382 -0.078052 -0.725193 0.538142\n7950 36.203691 0.214651 -0.913018 1.390701 -0.415739 -0.081818 -0.724303 0.543923\n7951 36.212045 0.213321 -0.912445 1.390357 -0.412846 -0.084716 -0.725045 0.544694\n7952 36.220556 0.212936 -0.912096 1.389770 -0.407206 -0.086926 -0.721818 0.552816\n7953 36.228066 0.211527 -0.911796 1.390213 -0.402729 -0.089832 -0.722305 0.554990\n7954 36.236911 0.210786 -0.911540 1.389779 -0.397281 -0.089520 -0.720393 0.561416\n7955 36.245096 0.209775 -0.911208 1.389598 -0.391641 -0.088601 -0.719482 0.566668\n7956 36.252229 0.208471 -0.910789 1.389616 -0.384254 -0.090935 -0.718673 0.572353\n7957 36.260800 0.207383 -0.910499 1.389682 -0.377860 -0.091652 -0.718094 0.577203\n7958 36.271273 0.205944 -0.910245 1.389784 -0.370566 -0.094632 -0.718370 0.581094\n7959 36.277991 0.204500 -0.909286 1.389739 -0.361292 -0.096179 -0.716418 0.589035\n7960 36.287340 0.202764 -0.908943 1.390153 -0.352461 -0.099620 -0.716147 0.594122\n7961 36.295460 0.201128 -0.907994 1.390526 -0.343240 -0.103878 -0.715522 0.599520\n7962 36.302380 0.199154 -0.908050 1.390949 -0.333994 -0.109232 -0.715587 0.603699\n7963 36.310839 0.197338 -0.906911 1.391211 -0.325042 -0.113335 -0.714108 0.609551\n7964 36.319852 0.195027 -0.905654 1.392000 -0.315881 -0.120328 -0.712549 0.614829\n7965 36.328682 0.192343 -0.905743 1.392210 -0.305607 -0.127420 -0.711254 0.620069\n7966 36.338111 0.190373 -0.904761 1.391844 -0.298511 -0.133415 -0.708082 0.625869\n7967 36.345299 0.188945 -0.904424 1.392038 -0.288133 -0.140424 -0.707260 0.630114\n7968 36.352833 0.186893 -0.903840 1.392320 -0.277734 -0.145664 -0.706430 0.634510\n7969 36.360840 0.184585 -0.903427 1.392562 -0.268725 -0.149237 -0.705888 0.638152\n7970 36.372971 0.182651 -0.902953 1.392778 -0.260193 -0.151405 -0.705773 0.641297\n7971 36.377996 0.180920 -0.902513 1.392914 -0.251142 -0.154275 -0.705989 0.643977\n7972 36.387377 0.178608 -0.901880 1.393382 -0.241984 -0.154834 -0.707669 0.645504\n7973 36.395671 0.176852 -0.901037 1.393536 -0.233037 -0.156453 -0.708606 0.647375\n7974 36.403567 0.174756 -0.900287 1.393903 -0.223148 -0.157686 -0.709449 0.649632\n7975 36.411848 0.172871 -0.899385 1.394313 -0.216004 -0.156880 -0.711050 0.650491\n7976 36.419036 0.170799 -0.898416 1.394930 -0.208504 -0.157840 -0.713569 0.649947\n7977 36.428403 0.168377 -0.897638 1.395095 -0.199820 -0.156822 -0.717250 0.648869\n7978 36.435809 0.166358 -0.896669 1.395635 -0.192555 -0.157825 -0.719373 0.648472\n7979 36.447193 0.164009 -0.895714 1.396204 -0.184378 -0.159041 -0.721893 0.647750\n7980 36.454225 0.161819 -0.894557 1.396677 -0.176718 -0.162512 -0.723148 0.647625\n7981 36.463499 0.159342 -0.893603 1.396948 -0.168152 -0.164320 -0.725740 0.646548\n7982 36.469487 0.157247 -0.892457 1.397439 -0.161549 -0.166950 -0.727732 0.645319\n7983 36.477133 0.154551 -0.891473 1.398111 -0.151820 -0.169285 -0.731137 0.643220\n7984 36.485807 0.151950 -0.890458 1.398229 -0.143813 -0.172754 -0.731717 0.643478\n7985 36.494989 0.149698 -0.889637 1.398266 -0.136531 -0.176810 -0.733026 0.642472\n7986 36.504053 0.147348 -0.888871 1.398725 -0.129895 -0.180566 -0.734150 0.641519\n7987 36.512846 0.144894 -0.887734 1.399124 -0.123878 -0.183868 -0.734958 0.640846\n7988 36.519703 0.142413 -0.886801 1.399277 -0.118052 -0.186059 -0.735553 0.640630\n7989 36.527682 0.139959 -0.886097 1.399429 -0.112283 -0.189697 -0.735738 0.640389\n7990 36.539118 0.137438 -0.885479 1.399123 -0.106054 -0.197697 -0.735536 0.639261\n7991 36.545052 0.134992 -0.885063 1.399079 -0.101005 -0.201436 -0.735509 0.638943\n7992 36.554423 0.132555 -0.884718 1.398831 -0.095492 -0.206077 -0.735070 0.638816\n7993 36.562749 0.129873 -0.884380 1.398786 -0.090432 -0.210224 -0.734494 0.638863\n7994 36.569179 0.127317 -0.884313 1.398835 -0.085088 -0.213914 -0.734105 0.638820\n7995 36.577483 0.125469 -0.884158 1.398677 -0.080701 -0.217972 -0.734291 0.637803\n7996 36.587364 0.123218 -0.884292 1.398516 -0.076406 -0.222414 -0.733758 0.637412\n7997 36.595735 0.120897 -0.884474 1.398412 -0.072150 -0.225224 -0.733904 0.636753\n7998 36.603757 0.118805 -0.884647 1.398212 -0.067973 -0.227761 -0.733928 0.636282\n7999 36.612420 0.116783 -0.884886 1.398079 -0.063959 -0.230311 -0.733852 0.635867\n8000 36.619237 0.116009 -0.885031 1.397593 -0.058734 -0.231859 -0.733426 0.636300\n8001 36.628843 0.113812 -0.886408 1.397255 -0.055130 -0.232014 -0.732970 0.637091\n8002 36.637180 0.111213 -0.886385 1.396982 -0.052598 -0.233737 -0.732480 0.637240\n8003 36.645466 0.109413 -0.886933 1.396739 -0.049992 -0.235126 -0.732618 0.636779\n8004 36.652688 0.107900 -0.888104 1.396521 -0.047637 -0.236493 -0.731978 0.637189\n8005 36.660737 0.105615 -0.888245 1.395538 -0.045369 -0.237347 -0.733063 0.635789\n8006 36.671405 0.104524 -0.890178 1.396175 -0.039725 -0.237797 -0.734064 0.634842\n8007 36.678826 0.103387 -0.890969 1.395499 -0.041634 -0.238622 -0.734383 0.634041\n8008 36.687427 0.101631 -0.892839 1.395365 -0.036373 -0.235803 -0.735858 0.633709\n8009 36.694899 0.100952 -0.893803 1.395151 -0.035173 -0.234361 -0.738585 0.631134\n8010 36.702734 0.099879 -0.893961 1.394122 -0.036321 -0.235097 -0.741062 0.627884\n8011 36.711896 0.098856 -0.896205 1.394649 -0.037840 -0.234258 -0.742896 0.625937\n8012 36.719819 0.097942 -0.897749 1.394353 -0.037353 -0.232556 -0.745887 0.623037\n8013 36.727863 0.097171 -0.899300 1.394053 -0.037355 -0.230598 -0.749387 0.619555\n8014 36.735762 0.096476 -0.901014 1.393604 -0.037572 -0.228066 -0.753147 0.615909\n8015 36.745628 0.095897 -0.902665 1.393247 -0.038803 -0.225811 -0.757871 0.610848\n8016 36.753216 0.095390 -0.904419 1.392855 -0.041115 -0.223594 -0.762919 0.605203\n8017 36.761891 0.095046 -0.906178 1.392441 -0.044896 -0.221384 -0.768421 0.598751\n8018 36.770195 0.094556 -0.908032 1.392182 -0.049865 -0.217878 -0.774556 0.591697\n8019 36.778600 0.094564 -0.910015 1.391776 -0.054778 -0.212993 -0.781027 0.584491\n8020 36.788144 0.095722 -0.911236 1.391581 -0.060078 -0.201599 -0.789456 0.576634\n8021 36.795750 0.095401 -0.913763 1.391170 -0.066739 -0.199691 -0.796091 0.567370\n8022 36.803917 0.095859 -0.915691 1.390918 -0.074131 -0.192735 -0.803903 0.557761\n8023 36.812226 0.096150 -0.917387 1.390795 -0.081436 -0.185975 -0.811623 0.547769\n8024 36.820550 0.095964 -0.919243 1.390511 -0.084595 -0.178510 -0.820311 0.536720\n8025 36.828858 0.096477 -0.920940 1.390412 -0.095010 -0.170782 -0.828434 0.524884\n8026 36.835782 0.096820 -0.922222 1.390205 -0.104047 -0.163528 -0.835910 0.513505\n8027 36.845421 0.097634 -0.924126 1.390207 0.113803 0.155696 0.844388 -0.499816\n8028 36.854424 0.098489 -0.925651 1.389987 0.123178 0.147966 0.852843 -0.485378\n8029 36.862446 0.098732 -0.926789 1.390231 0.132305 0.141065 0.860930 -0.470528\n8030 36.871385 0.099967 -0.927742 1.390280 0.142634 0.132430 0.869194 -0.454555\n8031 36.878629 0.100778 -0.928694 1.390254 0.153986 0.124258 0.876616 -0.438626\n8032 36.887499 0.102039 -0.929568 1.390547 0.166241 0.115967 0.883902 -0.421465\n8033 36.894908 0.102827 -0.930333 1.390380 0.175701 0.110496 0.890969 -0.403848\n8034 36.902370 0.104508 -0.930973 1.390826 0.188621 0.101532 0.898289 -0.383655\n8035 36.911834 0.105984 -0.931377 1.391052 0.205041 0.093757 0.903252 -0.365108\n8036 36.920015 0.108455 -0.931833 1.390536 0.222426 0.084695 0.908408 -0.343728\n8037 36.928660 0.109908 -0.932701 1.390617 0.238313 0.077431 0.912951 -0.322075\n8038 36.935727 0.111957 -0.933487 1.390653 0.252154 0.070718 0.917806 -0.298411\n8039 36.944911 0.113562 -0.934072 1.390607 0.266733 0.056533 0.922438 -0.273434\n8040 36.953834 0.115537 -0.935258 1.390142 0.282489 0.047475 0.925437 -0.248016\n8041 36.962165 0.117240 -0.935808 1.390092 0.297156 0.039695 0.927738 -0.222318\n8042 36.969006 0.118914 -0.936330 1.390283 0.307657 0.028630 0.930845 -0.195076\n8043 36.977977 0.121618 -0.936482 1.390175 0.319822 0.019052 0.932312 -0.167769\n8044 36.988047 0.122915 -0.937133 1.390180 0.332677 0.007293 0.932414 -0.140987\n8045 36.994424 0.124855 -0.937403 1.390209 0.344896 -0.003199 0.931884 -0.112379\n8046 37.002268 0.127137 -0.937784 1.390263 0.356411 -0.011530 0.930338 -0.085491\n8047 37.012580 0.129199 -0.937740 1.390273 0.369620 -0.021972 0.927127 -0.057746\n8048 37.020148 0.132597 -0.938374 1.389775 0.383463 -0.030577 0.922531 -0.030935\n8049 37.028488 0.133835 -0.937727 1.390322 0.394568 -0.038545 0.918050 -0.003818\n8050 37.035779 0.136621 -0.938294 1.390306 0.410769 -0.045817 0.910245 0.024973\n8051 37.045128 0.138909 -0.938330 1.390530 0.423779 -0.053514 0.902739 0.051078\n8052 37.052266 0.141686 -0.938208 1.390312 0.436900 -0.062162 0.893914 0.078562\n8053 37.060845 0.144116 -0.937832 1.390269 0.450655 -0.068752 0.883814 0.105146\n8054 37.068908 0.146888 -0.937829 1.390413 0.462872 -0.074441 0.873651 0.130161\n8055 37.077576 0.149682 -0.937489 1.390327 0.474189 -0.078947 0.863189 0.154328\n8056 37.088238 0.152815 -0.937498 1.390430 0.488680 -0.085558 0.849537 0.179329\n8057 37.095326 0.155766 -0.937606 1.390502 0.500861 -0.089037 0.836664 0.202985\n8058 37.102285 0.158407 -0.937438 1.390056 0.511580 -0.095896 0.822910 0.227835\n8059 37.111373 0.161026 -0.937435 1.389741 0.521618 -0.102221 0.808550 0.252413\n8060 37.118997 0.163710 -0.937317 1.389630 0.531036 -0.107902 0.793678 0.276468\n8061 37.127462 0.165955 -0.937221 1.389254 0.538560 -0.113626 0.779204 0.299804\n8062 37.138550 0.169079 -0.937671 1.389147 0.545553 -0.122429 0.762961 0.324460\n8063 37.144619 0.171454 -0.937649 1.388565 0.552267 -0.127114 0.746669 0.348322\n8064 37.153497 0.173852 -0.937741 1.388294 0.558475 -0.132646 0.729830 0.371293\n8065 37.162376 0.176162 -0.938043 1.387616 0.562315 -0.139218 0.713472 0.394180\n8066 37.169135 0.177996 -0.937995 1.387638 0.563759 -0.143499 0.698468 0.416805\n8067 37.179362 0.180141 -0.938169 1.386926 0.571094 -0.148978 0.678568 0.437268\n8068 37.186217 0.182144 -0.938240 1.386855 0.573157 -0.152952 0.661130 0.459350\n8069 37.194031 0.183783 -0.938258 1.386122 0.575877 -0.156477 0.642870 0.480208\n8070 37.202358 0.185628 -0.938353 1.385805 0.577117 -0.160566 0.624548 0.501094\n8071 37.211834 0.187023 -0.938904 1.385092 0.579162 -0.164983 0.603693 0.522405\n8072 37.218913 0.188269 -0.939502 1.383977 0.582086 -0.169444 0.581827 0.542164\n8073 37.227313 0.189713 -0.940012 1.383996 0.583057 -0.173379 0.560762 0.561721\n8074 37.238239 0.190774 -0.940657 1.383337 0.584777 -0.177969 0.538231 0.580233\n8075 37.245330 0.193022 -0.940785 1.382658 0.582766 -0.179027 0.518146 0.599882\n8076 37.253626 0.193472 -0.941327 1.381577 0.582249 -0.185355 0.493702 0.618780\n8077 37.262097 0.195140 -0.941918 1.381532 0.583328 -0.188566 0.470816 0.634431\n8078 37.268906 0.196615 -0.942895 1.381060 0.581234 -0.192756 0.445737 0.652940\n8079 37.277409 0.197857 -0.943333 1.380435 0.577142 -0.194130 0.423186 0.670921\n8080 37.285537 0.198672 -0.943879 1.380009 0.575342 -0.198063 0.398205 0.686429\n8081 37.295445 0.199872 -0.944327 1.379374 0.572011 -0.200811 0.374588 0.701543\n8082 37.304421 0.200255 -0.944713 1.378944 0.568097 -0.206669 0.349099 0.716019\n8083 37.311804 0.200348 -0.945183 1.379550 0.561739 -0.210201 0.325086 0.731153\n8084 37.319773 0.202124 -0.945404 1.378305 0.559473 -0.211112 0.302825 0.742105\n8085 37.327455 0.202594 -0.945608 1.378032 0.554247 -0.214644 0.279064 0.754229\n8086 37.338921 0.203083 -0.945751 1.377720 0.549733 -0.219287 0.255663 0.764424\n8087 37.344906 0.203493 -0.945515 1.377003 0.542466 -0.224103 0.234586 0.774905\n8088 37.352305 0.204583 -0.945446 1.377361 0.536990 -0.226551 0.213134 0.784149\n8089 37.361033 0.205375 -0.945744 1.377473 0.531123 -0.228318 0.191694 0.793116\n8090 37.370735 0.206200 -0.945752 1.377084 0.522856 -0.229246 0.170722 0.803070\n8091 37.377407 0.207147 -0.945421 1.377151 0.515667 -0.232932 0.150888 0.810594\n8092 37.385776 0.207302 -0.945016 1.377112 0.505722 -0.235237 0.128860 0.819941\n8093 37.394766 0.208561 -0.944722 1.376800 0.497069 -0.237924 0.109334 0.827261\n8094 37.402397 0.209315 -0.944228 1.376714 0.487157 -0.239217 0.090080 0.835068\n8095 37.412708 0.210281 -0.943463 1.376307 0.477117 -0.243277 0.071513 0.841464\n8096 37.419995 0.211468 -0.942665 1.377041 0.467023 -0.243944 0.053154 0.848266\n8097 37.428555 0.212282 -0.941658 1.377304 0.456381 -0.244914 0.036001 0.854656\n8098 37.436537 0.213212 -0.940224 1.377630 0.444868 -0.249202 0.017591 0.860047\n8099 37.445383 0.214072 -0.938977 1.378227 0.433300 -0.248018 0.002436 0.866448\n8100 37.453692 0.215043 -0.937634 1.378766 0.421501 -0.250282 -0.012390 0.871518\n8101 37.461481 0.215954 -0.936159 1.379350 0.408702 -0.251308 -0.026276 0.876993\n8102 37.472876 0.216431 -0.934748 1.379714 0.394895 -0.251285 -0.040823 0.882750\n8103 37.478251 0.218104 -0.933112 1.380235 0.383188 -0.254047 -0.052520 0.886493\n8104 37.485986 0.219249 -0.931873 1.380582 0.369063 -0.252198 -0.064086 0.892234\n8105 37.496144 0.220427 -0.930305 1.381081 0.356098 -0.252477 -0.075425 0.896527\n8106 37.503692 0.221370 -0.927792 1.381717 0.341963 -0.255544 -0.086842 0.900121\n8107 37.510634 0.222878 -0.926828 1.382135 0.329339 -0.253969 -0.097340 0.904190\n8108 37.521138 0.224058 -0.924921 1.382746 0.315349 -0.254873 -0.107631 0.907750\n8109 37.528210 0.225371 -0.922954 1.383192 0.301332 -0.255939 -0.117865 0.910935\n8110 37.537049 0.226472 -0.921157 1.383862 0.287133 -0.256540 -0.127587 0.914037\n8111 37.545579 0.227492 -0.919552 1.384235 0.273287 -0.257436 -0.137264 0.916624\n8112 37.552401 0.228805 -0.917798 1.385070 0.260029 -0.256655 -0.146979 0.919190\n8113 37.562756 0.230210 -0.916012 1.385479 0.246125 -0.257948 -0.156122 0.921147\n8114 37.570067 0.231590 -0.913861 1.386088 0.232810 -0.257566 -0.166174 0.922955\n8115 37.579350 0.232999 -0.912179 1.386703 0.220228 -0.257403 -0.175834 0.924297\n8116 37.586163 0.234385 -0.910180 1.387240 0.207806 -0.256503 -0.185672 0.925499\n8117 37.594420 0.235961 -0.908290 1.387765 0.195183 -0.255678 -0.195900 0.926367\n8118 37.602356 0.237537 -0.906381 1.388145 0.182364 -0.253117 -0.205657 0.927567\n8119 37.611268 0.239080 -0.904466 1.388506 0.169686 -0.250061 -0.216183 0.928408\n8120 37.620078 0.241291 -0.902835 1.388716 0.156785 -0.247269 -0.225028 0.929322\n8121 37.627285 0.242706 -0.900511 1.389057 0.143835 -0.243932 -0.234919 0.929850\n8122 37.636252 0.244512 -0.898558 1.389377 0.131648 -0.238776 -0.244043 0.930644\n8123 37.645101 0.246437 -0.896769 1.389727 0.121812 -0.233343 -0.253003 0.930968\n8124 37.652348 0.248418 -0.895038 1.390044 0.111679 -0.226935 -0.261390 0.931506\n8125 37.661960 0.250404 -0.893300 1.390206 0.102152 -0.220777 -0.269133 0.931874\n8126 37.670248 0.252592 -0.891732 1.390155 0.092624 -0.214403 -0.276792 0.932115\n8127 37.678475 0.254811 -0.890016 1.390198 0.083751 -0.208576 -0.284164 0.932058\n8128 37.688126 0.256881 -0.888580 1.390728 0.076998 -0.199142 -0.290344 0.932799\n8129 37.695112 0.259480 -0.887145 1.390854 0.069906 -0.189970 -0.297055 0.933157\n8130 37.703651 0.261529 -0.885699 1.390445 0.059731 -0.182908 -0.303001 0.933363\n8131 37.711356 0.263642 -0.884431 1.390669 0.052587 -0.175119 -0.309047 0.933305\n8132 37.720230 0.265876 -0.882916 1.390870 0.045710 -0.165942 -0.314787 0.933425\n8133 37.728514 0.267991 -0.881439 1.390872 0.038601 -0.157578 -0.320375 0.933295\n8134 37.736291 0.270137 -0.879952 1.390641 0.030848 -0.150081 -0.324989 0.933223\n8135 37.746006 0.272064 -0.878362 1.390744 0.024065 -0.142938 -0.330412 0.932640\n8136 37.752912 0.273926 -0.876944 1.390417 0.016537 -0.135870 -0.334880 0.932267\n8137 37.760898 0.275891 -0.875544 1.390141 0.009113 -0.129420 -0.339090 0.931765\n8138 37.768879 0.277610 -0.874005 1.389999 0.001284 -0.122856 -0.343314 0.931150\n8139 37.778592 0.279705 -0.872471 1.389895 -0.005679 -0.117347 -0.347089 0.930444\n8140 37.787011 0.281397 -0.871113 1.389742 -0.012472 -0.111661 -0.350115 0.929944\n8141 37.795138 0.282817 -0.869715 1.389633 -0.018508 -0.107107 -0.353163 0.929226\n8142 37.802890 0.284404 -0.868427 1.389440 -0.023957 -0.104315 -0.354364 0.928962\n8143 37.810571 0.285637 -0.867109 1.389284 -0.028533 -0.100794 -0.355380 0.928834\n8144 37.820004 0.286568 -0.866273 1.389144 -0.031934 -0.098309 -0.355940 0.928775\n8145 37.828556 0.288049 -0.865087 1.389253 -0.034366 -0.095986 -0.356083 0.928876\n8146 37.835698 0.289227 -0.864028 1.389193 -0.036620 -0.092948 -0.355390 0.929364\n8147 37.844197 0.290308 -0.863119 1.389110 -0.038884 -0.090500 -0.354251 0.929948\n8148 37.855562 0.291516 -0.861854 1.389083 -0.039730 -0.086466 -0.354174 0.930326\n8149 37.861861 0.292491 -0.860782 1.388829 -0.042274 -0.083665 -0.351756 0.931387\n8150 37.870294 0.293754 -0.859514 1.388974 -0.041891 -0.079280 -0.349732 0.932549\n8151 37.878033 0.294362 -0.858552 1.388947 -0.044865 -0.076656 -0.347506 0.933462\n8152 37.885646 0.295425 -0.857328 1.388973 -0.045320 -0.073488 -0.345351 0.934494\n8153 37.896033 0.296172 -0.856486 1.388961 -0.045321 -0.071299 -0.342215 0.935816\n8154 37.902866 0.297066 -0.855404 1.389130 -0.045092 -0.068954 -0.339850 0.936864\n8155 37.910594 0.297354 -0.854621 1.389214 -0.044875 -0.067671 -0.336677 0.938113\n8156 37.919282 0.297933 -0.853897 1.389312 -0.044288 -0.067035 -0.333413 0.939351\n8157 37.928303 0.298222 -0.853324 1.389497 -0.043693 -0.066483 -0.329939 0.940644\n8158 37.935760 0.298214 -0.852817 1.389640 -0.042885 -0.067273 -0.326080 0.941970\n8159 37.945566 0.298433 -0.852313 1.389658 -0.040882 -0.069385 -0.321754 0.943392\n8160 37.953197 0.298670 -0.852087 1.390121 -0.038864 -0.068324 -0.318996 0.944491\n8161 37.961970 0.298610 -0.851641 1.390692 -0.036645 -0.068352 -0.315226 0.945843\n8162 37.968962 0.298319 -0.851357 1.390733 -0.034679 -0.069507 -0.310668 0.947339\n8163 37.978133 0.297996 -0.850857 1.391369 -0.030461 -0.070180 -0.305358 0.949159\n8164 37.985743 0.297862 -0.850569 1.391747 -0.025339 -0.069822 -0.299548 0.951185\n8165 37.994239 0.297515 -0.850075 1.392549 -0.019481 -0.068693 -0.293453 0.953303\n8166 38.005446 0.297121 -0.849529 1.393149 -0.013072 -0.069325 -0.285805 0.955688\n8167 38.011092 0.296721 -0.849134 1.393893 -0.005574 -0.067844 -0.277292 0.958371\n8168 38.020383 0.295869 -0.848773 1.394537 0.002209 -0.068671 -0.267614 0.961073\n8169 38.028914 0.295199 -0.848446 1.395064 0.010149 -0.068311 -0.256595 0.964049\n8170 38.035890 0.294221 -0.848273 1.395874 0.018207 -0.068036 -0.244662 0.967047\n8171 38.045343 0.293167 -0.847857 1.396452 0.027567 -0.069539 -0.231521 0.969950\n8172 38.054811 0.291785 -0.848040 1.397240 0.038738 -0.069180 -0.217316 0.972876\n8173 38.062055 0.290174 -0.847932 1.398250 0.051444 -0.069511 -0.202704 0.975414\n8174 38.070743 0.288743 -0.847665 1.399206 0.061281 -0.071953 -0.185734 0.978044\n8175 38.078272 0.287077 -0.847863 1.399796 0.073535 -0.073830 -0.169426 0.980019\n8176 38.086996 0.285287 -0.848057 1.400759 0.085357 -0.076376 -0.152582 0.981631\n8177 38.095078 0.283457 -0.848398 1.401428 0.098673 -0.078721 -0.132795 0.983073\n8178 38.102228 0.281613 -0.848343 1.402368 0.110939 -0.080624 -0.114881 0.983867\n8179 38.111102 0.279060 -0.848680 1.403244 0.123040 -0.085447 -0.095502 0.984093\n8180 38.120311 0.276746 -0.848911 1.404038 0.134971 -0.087689 -0.075406 0.984077\n8181 38.127280 0.274276 -0.849320 1.404775 0.147545 -0.089992 -0.054757 0.983430\n8182 38.135737 0.271700 -0.849774 1.405330 0.158726 -0.093527 -0.033979 0.982295\n8183 38.144916 0.269382 -0.850523 1.406077 0.172127 -0.094630 -0.013090 0.980432\n8184 38.152429 0.266798 -0.851286 1.406732 0.184420 -0.097172 0.008876 0.977992\n8185 38.160678 0.264166 -0.851907 1.407187 0.196388 -0.100176 0.030449 0.974920\n8186 38.170351 0.261804 -0.853090 1.407783 0.209708 -0.100295 0.052859 0.971169\n8187 38.178550 0.259013 -0.854160 1.408316 0.221389 -0.103277 0.074775 0.966814\n8188 38.185591 0.256571 -0.855441 1.408818 0.233015 -0.102846 0.097457 0.962096\n8189 38.195441 0.254223 -0.856790 1.409263 0.245236 -0.100943 0.120632 0.956618\n8190 38.203775 0.251546 -0.858161 1.409317 0.256140 -0.101526 0.143695 0.950493\n8191 38.211951 0.249264 -0.859107 1.409868 0.265595 -0.099898 0.167593 0.944136\n8192 38.220165 0.246756 -0.859973 1.410444 0.275116 -0.098149 0.190575 0.937208\n8193 38.228490 0.243910 -0.861517 1.410419 0.284088 -0.097151 0.213931 0.929564\n8194 38.238551 0.241306 -0.862121 1.410628 0.291425 -0.094839 0.236569 0.922015\n8195 38.244550 0.238885 -0.863731 1.410904 0.301335 -0.092636 0.260713 0.912494\n8196 38.253402 0.237042 -0.865127 1.411085 0.309566 -0.086315 0.284604 0.903172\n8197 38.262904 0.234697 -0.866331 1.411241 0.317104 -0.081080 0.307567 0.893461\n8198 38.269890 0.232002 -0.867231 1.411525 0.322079 -0.078776 0.329659 0.883960\n8199 38.278576 0.229094 -0.868633 1.411475 0.326883 -0.075481 0.352528 0.873599\n8200 38.286836 0.227212 -0.869940 1.411629 0.332501 -0.066693 0.376034 0.862319\n8201 38.296092 0.224557 -0.871275 1.411742 0.334939 -0.062784 0.398396 0.851560\n8202 38.303624 0.221749 -0.872745 1.411861 0.337125 -0.057924 0.421543 0.839817\n8203 38.311440 0.218778 -0.874400 1.411951 0.337349 -0.053924 0.443217 0.828762\n8204 38.320005 0.216168 -0.876059 1.412114 0.337807 -0.046845 0.464989 0.816993\n8205 38.328392 0.212577 -0.877768 1.412181 0.336730 -0.045406 0.485701 0.805385\n8206 38.335627 0.210354 -0.879651 1.412148 0.336732 -0.036507 0.507339 0.792392\n8207 38.344912 0.207637 -0.881603 1.412050 0.335499 -0.029268 0.528707 0.779136\n8208 38.353570 0.204539 -0.883663 1.412096 0.334453 -0.026085 0.547987 0.766271\n8209 38.360616 0.201675 -0.885644 1.411981 0.332877 -0.019006 0.567594 0.752774\n8210 38.369088 0.198254 -0.887706 1.411999 0.331985 -0.013796 0.588961 0.736696\n8211 38.378186 0.195952 -0.889506 1.411757 0.327251 -0.001433 0.608903 0.722594\n8212 38.385854 0.192619 -0.891750 1.411781 0.324900 0.005636 0.630402 0.704983\n8213 38.394066 0.189259 -0.894050 1.411833 0.320329 0.013587 0.650264 0.688739\n8214 38.403375 0.185576 -0.896762 1.411850 0.315615 0.019534 0.669278 0.672364\n8215 38.411821 0.182365 -0.899548 1.411675 0.311558 0.025749 0.687707 0.655231\n8216 38.420243 0.178911 -0.902242 1.411562 0.303271 0.034778 0.706568 0.638418\n8217 38.427871 0.175683 -0.905741 1.411573 0.296619 0.039165 0.723878 0.621678\n8218 38.435653 0.171091 -0.908586 1.411869 0.285090 0.047284 0.741924 0.605010\n8219 38.446042 0.168895 -0.913108 1.410679 0.284637 0.051122 0.757699 0.585030\n8220 38.452928 0.165057 -0.915375 1.411352 0.271183 0.058907 0.775061 0.567688\n8221 38.462064 0.162031 -0.919537 1.411193 0.263469 0.064067 0.790288 0.549476\n8222 38.468927 0.158653 -0.923472 1.410893 0.252604 0.069845 0.805952 0.530806\n8223 38.478540 0.156573 -0.927482 1.410615 0.242575 0.075098 0.820663 0.511888\n8224 38.485535 0.153143 -0.932219 1.410884 0.232998 0.079388 0.834567 0.492856\n8225 38.494356 0.150412 -0.936670 1.410733 0.223264 0.085593 0.847658 0.473608\n8226 38.503007 0.147872 -0.941488 1.410633 0.212953 0.092113 0.860884 0.452820\n8227 38.510738 0.145316 -0.945841 1.410508 0.202619 0.099261 0.872594 0.433212\n8228 38.520251 0.142846 -0.950821 1.409979 0.195528 0.104627 0.882998 0.413688\n8229 38.528474 0.140653 -0.955841 1.409437 0.188059 0.111313 0.892734 0.394042\n8230 38.536875 0.138483 -0.960746 1.409158 0.182797 0.117264 0.901590 0.374126\n8231 38.545020 0.136626 -0.965853 1.408668 0.176217 0.124339 0.909923 0.354298\n8232 38.552295 0.134911 -0.970639 1.408227 0.165837 0.133549 0.917974 0.334644\n8233 38.560674 0.133239 -0.975691 1.407714 0.160438 0.138518 0.925323 0.314404\n8234 38.570893 0.131457 -0.981793 1.407176 0.154061 0.144575 0.931721 0.295398\n8235 38.578589 0.130340 -0.986495 1.406292 0.147392 0.150164 0.937747 0.276329\n8236 38.586970 0.128577 -0.991768 1.405849 0.132709 0.154249 0.944603 0.257528\n8237 38.594892 0.127487 -0.997110 1.404526 0.134592 0.162007 0.947884 0.239070\n8238 38.602258 0.125261 -1.002673 1.404078 0.119164 0.166398 0.953686 0.220444\n8239 38.610802 0.124342 -1.008151 1.403067 0.118514 0.173420 0.956713 0.201447\n8240 38.623144 0.123225 -1.012439 1.401663 0.104827 0.179281 0.960611 0.184650\n8241 38.628146 0.121204 -1.018308 1.401038 0.099465 0.186338 0.963690 0.163358\n8242 38.636897 0.118935 -1.022964 1.400604 0.084935 0.193402 0.966143 0.148156\n8243 38.645271 0.117491 -1.027710 1.399990 0.072050 0.199608 0.968537 0.130008\n8244 38.652295 0.115891 -1.032623 1.399324 0.061950 0.207548 0.969608 0.113786\n8245 38.661901 0.114782 -1.037859 1.398450 0.057955 0.216237 0.969704 0.097764\n8246 38.670089 0.113032 -1.042348 1.398068 0.042774 0.223462 0.970208 0.083261\n8247 38.679394 0.111844 -1.047073 1.397604 0.034915 0.230222 0.970083 0.068687\n8248 38.687052 0.110476 -1.051653 1.397061 0.027110 0.237244 0.969564 0.054088\n8249 38.695439 0.109920 -1.056251 1.396654 0.023240 0.244241 0.968565 0.041082\n8250 38.703479 0.108901 -1.060518 1.396090 0.019008 0.251045 0.967384 0.028002\n8251 38.711678 0.107587 -1.064196 1.396102 0.013178 0.256491 0.966341 0.014983\n8252 38.718935 0.107384 -1.068319 1.395919 0.012128 0.262439 0.964865 0.003712\n8253 38.727265 0.106799 -1.071989 1.395703 0.012081 0.266926 0.963594 -0.009568\n8254 38.737059 0.106360 -1.075698 1.395628 0.014747 0.269561 0.962634 -0.021322\n8255 38.744767 0.105602 -1.079069 1.395754 0.009362 0.270688 0.962083 -0.032184\n8256 38.752221 0.105605 -1.082558 1.395853 0.013781 0.272738 0.961024 -0.043100\n8257 38.760714 0.106257 -1.086631 1.396135 0.019348 0.274314 0.959953 -0.053559\n8258 38.768900 0.105901 -1.089298 1.395846 0.025626 0.278182 0.958006 -0.064673\n8259 38.777475 0.105850 -1.092249 1.396098 0.029605 0.282179 0.956006 -0.074505\n8260 38.786638 0.105927 -1.095293 1.396189 0.030540 0.284485 0.954325 -0.086024\n8261 38.796047 0.105858 -1.098072 1.396289 0.032231 0.288067 0.952161 -0.096788\n8262 38.802523 0.106468 -1.100956 1.396517 0.034180 0.292457 0.949596 -0.107560\n8263 38.811808 0.106474 -1.103613 1.396640 0.033572 0.296473 0.947110 -0.118152\n8264 38.819536 0.106180 -1.105945 1.396981 0.027938 0.300412 0.944536 -0.129708\n8265 38.827435 0.106779 -1.108209 1.397272 0.025049 0.303786 0.941912 -0.141025\n8266 38.837616 0.106730 -1.110316 1.398046 0.023105 0.305443 0.939592 -0.152771\n8267 38.844521 0.108330 -1.112159 1.397518 0.020118 0.310514 0.936058 -0.164234\n8268 38.853889 0.107975 -1.114331 1.397486 0.015241 0.314624 0.933176 -0.173093\n8269 38.861909 0.108923 -1.115579 1.398362 0.011360 0.314430 0.930304 -0.188519\n8270 38.869354 0.109110 -1.116767 1.398797 0.010951 0.322044 0.925132 -0.200744\n8271 38.879306 0.109641 -1.118147 1.399256 0.009868 0.324966 0.921323 -0.213220\n8272 38.886641 0.110388 -1.119376 1.399747 0.011377 0.327794 0.917416 -0.225321\n8273 38.895982 0.111143 -1.120540 1.400150 0.017401 0.330822 0.913122 -0.237619\n8274 38.903439 0.112000 -1.121487 1.400933 0.019123 0.332978 0.909238 -0.249091\n8275 38.911327 0.112565 -1.122289 1.401608 0.019456 0.335362 0.905389 -0.259661\n8276 38.920135 0.113730 -1.123332 1.401609 0.031253 0.335787 0.901887 -0.269946\n8277 38.928560 0.114805 -1.123793 1.402407 0.036164 0.335750 0.898808 -0.279479\n8278 38.935630 0.115791 -1.124015 1.403352 0.040598 0.338484 0.894799 -0.288299\n8279 38.945627 0.116270 -1.124516 1.404641 0.044474 0.340557 0.891192 -0.296344\n8280 38.953717 0.117574 -1.124973 1.405356 0.052553 0.341126 0.887958 -0.303976\n8281 38.960798 0.118283 -1.124834 1.406506 0.056939 0.341453 0.885454 -0.310063\n8282 38.969911 0.119217 -1.124887 1.407643 0.064573 0.344363 0.881481 -0.316600\n8283 38.978935 0.119995 -1.124597 1.408918 0.068324 0.345066 0.879300 -0.321081\n8284 38.985740 0.121031 -1.124231 1.409933 0.076829 0.345293 0.876961 -0.325283\n8285 38.994203 0.122002 -1.123920 1.411391 0.082446 0.346322 0.874705 -0.328868\n8286 39.004159 0.123419 -1.123493 1.412303 0.090867 0.345832 0.873221 -0.331101\n8287 39.011467 0.123843 -1.122709 1.413939 0.094652 0.345942 0.872092 -0.332898\n8288 39.020169 0.124044 -1.122251 1.414755 0.101752 0.345020 0.870989 -0.334642\n8289 39.028106 0.125535 -1.121083 1.416117 0.108379 0.343949 0.870440 -0.335093\n8290 39.036711 0.125905 -1.120003 1.417954 0.112020 0.343665 0.870091 -0.335094\n8291 39.044568 0.127097 -1.118867 1.419110 0.122062 0.341107 0.870518 -0.333086\n8292 39.053429 0.127703 -1.117747 1.420558 0.127110 0.339644 0.870902 -0.331684\n8293 39.062372 0.128667 -1.116710 1.421401 0.137337 0.337268 0.870970 -0.329849\n8294 39.069767 0.129446 -1.115161 1.422876 0.142645 0.335491 0.871703 -0.327464\n8295 39.080098 0.130259 -1.114069 1.423896 0.150932 0.333358 0.872235 -0.324498\n8296 39.086233 0.131246 -1.112446 1.425661 0.153549 0.331879 0.873793 -0.320571\n8297 39.094000 0.132308 -1.111025 1.426827 0.160682 0.329439 0.875043 -0.316150\n8298 39.102328 0.133310 -1.109468 1.427743 0.169653 0.326774 0.876022 -0.311484\n8299 39.112388 0.134575 -1.108237 1.428853 0.176493 0.323792 0.877777 -0.305804\n8300 39.118917 0.135771 -1.106773 1.429733 0.185115 0.321384 0.878778 -0.300323\n8301 39.127187 0.136803 -1.105273 1.431170 0.189609 0.320294 0.880420 -0.293804\n8302 39.137503 0.138580 -1.103791 1.431830 0.199955 0.316178 0.882097 -0.286276\n8303 39.144956 0.139528 -1.102095 1.432728 0.206754 0.313492 0.883712 -0.279336\n8304 39.153663 0.140635 -1.100372 1.433883 0.214019 0.309982 0.885323 -0.272599\n8305 39.162602 0.141817 -1.098592 1.434649 0.220602 0.305537 0.887523 -0.265112\n8306 39.169121 0.142827 -1.096537 1.435264 0.224776 0.302548 0.889555 -0.258132\n8307 39.179275 0.144112 -1.095273 1.436085 0.230819 0.297549 0.891768 -0.250872\n8308 39.187207 0.145475 -1.093532 1.437201 0.235732 0.293382 0.893775 -0.243975\n8309 39.194725 0.146486 -1.091787 1.436886 0.244849 0.285218 0.896267 -0.235383\n8310 39.202340 0.147454 -1.090125 1.437633 0.251122 0.281873 0.897159 -0.229327\n8311 39.212142 0.148447 -1.088600 1.438699 0.256748 0.276362 0.899079 -0.222175\n8312 39.219524 0.149210 -1.087135 1.439354 0.260956 0.271525 0.900952 -0.215552\n8313 39.227372 0.150233 -1.085711 1.439907 0.266357 0.265661 0.902725 -0.208726\n8314 39.237401 0.151138 -1.084498 1.440410 0.270574 0.259529 0.904688 -0.202421\n8315 39.245285 0.151856 -1.083073 1.440918 0.272892 0.252929 0.907344 -0.195664\n8316 39.253461 0.152833 -1.081780 1.441159 0.277655 0.247244 0.908884 -0.188966\n8317 39.262315 0.153700 -1.080595 1.441477 0.281004 0.240017 0.911056 -0.182771\n8318 39.268996 0.154508 -1.078685 1.441589 0.284604 0.234763 0.912660 -0.175893\n8319 39.277161 0.155517 -1.078501 1.441715 0.289278 0.227753 0.914079 -0.170018\n8320 39.287638 0.156608 -1.077131 1.441592 0.292209 0.220832 0.916061 -0.163339\n8321 39.294960 0.157960 -1.076064 1.441035 0.296047 0.212262 0.917896 -0.157377\n8322 39.303536 0.159504 -1.074905 1.440751 0.300696 0.206057 0.918768 -0.151617\n8323 39.312015 0.159903 -1.074300 1.440869 0.301525 0.199711 0.921123 -0.143984\n8324 39.319070 0.161337 -1.073296 1.440241 0.305176 0.192006 0.922566 -0.137379\n8325 39.328767 0.162333 -1.073039 1.440149 0.310012 0.185621 0.923149 -0.131274\n8326 39.336200 0.163194 -1.072317 1.439750 0.310363 0.179113 0.925184 -0.125010\n8327 39.344283 0.164858 -1.072327 1.438980 0.314070 0.170991 0.926379 -0.118082\n8328 39.353240 0.166054 -1.071359 1.437896 0.314944 0.164175 0.928134 -0.111460\n8329 39.361748 0.167124 -1.071608 1.437403 0.318493 0.157098 0.928757 -0.106266\n8330 39.368932 0.168418 -1.071630 1.436237 0.319344 0.148950 0.930531 -0.099724\n8331 39.377565 0.169954 -1.071468 1.435564 0.321507 0.143978 0.931184 -0.093806\n8332 39.386844 0.171038 -1.071627 1.434836 0.323963 0.137021 0.931979 -0.087686\n8333 39.394230 0.172010 -1.071836 1.434001 0.325233 0.130462 0.932962 -0.082368\n8334 39.404265 0.173070 -1.072079 1.433025 0.326484 0.124673 0.933792 -0.076795\n8335 39.411543 0.173813 -1.072591 1.432086 0.327313 0.118143 0.934762 -0.071610\n8336 39.419999 0.175272 -1.073528 1.430966 0.328693 0.112143 0.935430 -0.065995\n8337 39.427733 0.175531 -1.074064 1.430090 0.324883 0.104939 0.938055 -0.059092\n8338 39.435666 0.176706 -1.075161 1.429057 0.328639 0.099628 0.937612 -0.054362\n8339 39.445308 0.177353 -1.075966 1.427786 0.325877 0.093604 0.939501 -0.048789\n8340 39.453477 0.178067 -1.077221 1.426701 0.325217 0.085589 0.940781 -0.042888\n8341 39.461609 0.178730 -1.078524 1.425507 0.324336 0.076346 0.942157 -0.036299\n8342 39.470071 0.179537 -1.079968 1.424088 0.325906 0.069989 0.942269 -0.031858\n8343 39.478536 0.180632 -1.081573 1.422555 0.326324 0.061308 0.942832 -0.028668\n8344 39.485638 0.180890 -1.082783 1.420834 0.330245 0.053066 0.942184 -0.020273\n8345 39.493935 0.181257 -1.084439 1.419709 0.325505 0.045189 0.944320 -0.016246\n8346 39.502124 0.181610 -1.086063 1.418541 0.325069 0.037868 0.944866 -0.011198\n8347 39.511704 0.182303 -1.087972 1.416861 0.328402 0.030099 0.944041 -0.005718\n8348 39.520223 0.182341 -1.089341 1.415941 0.323267 0.024529 0.945988 -0.001615\n8349 39.528518 0.182863 -1.091819 1.414453 0.328237 0.015751 0.944450 0.005115\n8350 39.536466 0.183375 -1.093619 1.412926 0.330364 0.008352 0.943753 0.010987\n8351 39.544018 0.183493 -1.095502 1.411445 0.329776 0.001274 0.943892 0.017739\n8352 39.553164 0.183214 -1.098015 1.410214 0.330970 -0.006469 0.943339 0.022992\n8353 39.561883 0.182858 -1.099865 1.408742 0.329122 -0.014187 0.943775 0.027687\n8354 39.568916 0.183416 -1.102397 1.407035 0.333758 -0.019813 0.941917 0.031706\n8355 39.577245 0.182676 -1.104700 1.405665 0.332170 -0.027671 0.942069 0.037465\n8356 39.587024 0.183074 -1.107346 1.404385 0.335699 -0.034669 0.940367 0.042595\n8357 39.594453 0.182736 -1.109961 1.402958 0.335357 -0.041180 0.939979 0.047752\n8358 39.603666 0.182393 -1.112654 1.401547 0.335070 -0.047725 0.939471 0.053341\n8359 39.612011 0.181918 -1.115402 1.400114 0.334655 -0.054339 0.938920 0.059017\n8360 39.619038 0.181441 -1.118236 1.398631 0.334465 -0.060850 0.938187 0.065086\n8361 39.627309 0.180720 -1.120954 1.397146 0.333784 -0.066892 0.937606 0.070776\n8362 39.636914 0.179751 -1.123930 1.395658 0.333173 -0.072212 0.936960 0.076731\n8363 39.645146 0.179093 -1.126943 1.394138 0.336364 -0.075838 0.935183 0.080872\n8364 39.652278 0.178388 -1.130049 1.392629 0.331536 -0.084876 0.935618 0.086597\n8365 39.662483 0.177026 -1.133161 1.391528 0.330026 -0.089960 0.934877 0.094842\n8366 39.669647 0.176222 -1.135617 1.390155 0.331316 -0.096785 0.933484 0.097312\n8367 39.677146 0.176131 -1.139384 1.388215 0.335616 -0.101389 0.930917 0.102352\n8368 39.685770 0.175057 -1.142019 1.387002 0.335702 -0.105702 0.929996 0.106010\n8369 39.695429 0.173319 -1.145290 1.385682 0.334372 -0.111998 0.928744 0.114393\n8370 39.702877 0.172071 -1.148672 1.383425 0.336546 -0.117351 0.926480 0.120830\n8371 39.711855 0.170493 -1.150795 1.382367 0.338214 -0.122313 0.924982 0.122720\n8372 39.719842 0.169203 -1.154313 1.380931 0.335470 -0.127481 0.924566 0.128008\n8373 39.727421 0.167626 -1.157774 1.378758 0.337617 -0.134387 0.922160 0.132575\n8374 39.736276 0.165773 -1.160751 1.377457 0.336840 -0.138358 0.921135 0.137500\n8375 39.745487 0.164709 -1.163332 1.375828 0.339645 -0.141321 0.919476 0.138686\n8376 39.752579 0.163126 -1.167068 1.374341 0.337236 -0.146352 0.918651 0.144682\n8377 39.762071 0.161267 -1.170290 1.372347 0.340262 -0.148940 0.916398 0.149177\n8378 39.769629 0.159873 -1.173518 1.370690 0.338515 -0.152278 0.916424 0.149620\n8379 39.777401 0.158043 -1.176797 1.368765 0.338041 -0.157480 0.915200 0.152767\n8380 39.787432 0.156175 -1.179942 1.366873 0.338131 -0.161405 0.914001 0.155619\n8381 39.795167 0.154016 -1.183004 1.364905 0.338124 -0.166045 0.912648 0.158665\n8382 39.802298 0.151986 -1.186059 1.363020 0.337687 -0.170264 0.911807 0.159952\n8383 39.810670 0.150008 -1.188947 1.360503 0.340679 -0.178345 0.908714 0.162390\n8384 39.820315 0.147325 -1.192037 1.359113 0.336546 -0.179729 0.909728 0.163799\n8385 39.828112 0.144871 -1.194929 1.357211 0.335620 -0.184471 0.908817 0.165476\n8386 39.836794 0.142067 -1.197806 1.355208 0.335951 -0.189514 0.906980 0.169143\n8387 39.845370 0.139192 -1.199956 1.352831 0.334669 -0.194676 0.906356 0.169166\n8388 39.852890 0.137008 -1.202852 1.351077 0.333379 -0.196849 0.906028 0.170948\n8389 39.860453 0.134127 -1.205734 1.348809 0.333192 -0.202757 0.904845 0.170671\n8390 39.870687 0.131410 -1.208107 1.346840 0.332548 -0.206343 0.904292 0.170561\n8391 39.878003 0.129074 -1.210473 1.344784 0.332237 -0.210199 0.903529 0.170499\n8392 39.886719 0.126317 -1.212833 1.342739 0.332688 -0.213357 0.902567 0.170792\n8393 39.895458 0.123154 -1.214965 1.341064 0.329730 -0.216381 0.902801 0.171489\n8394 39.903027 0.120521 -1.217263 1.338835 0.330764 -0.220452 0.901556 0.170857\n8395 39.912468 0.117494 -1.219305 1.337303 0.328766 -0.222233 0.901564 0.172361\n8396 39.919412 0.114590 -1.221385 1.335645 0.329670 -0.225686 0.900261 0.172955\n8397 39.927295 0.110756 -1.222660 1.333776 0.324008 -0.229906 0.901179 0.173318\n8398 39.936236 0.108423 -1.224860 1.331702 0.323910 -0.231785 0.900742 0.173271\n8399 39.944404 0.105295 -1.226430 1.329854 0.322204 -0.234662 0.900683 0.172882\n8400 39.952886 0.102615 -1.227790 1.327961 0.321630 -0.238479 0.899626 0.174227\n8401 39.960552 0.099154 -1.230214 1.325635 0.320610 -0.242701 0.898803 0.174525\n8402 39.970097 0.096111 -1.231778 1.323759 0.320283 -0.245413 0.898059 0.175161\n8403 39.978151 0.093121 -1.233107 1.322113 0.318684 -0.245337 0.898564 0.175594\n8404 39.986812 0.089815 -1.234840 1.319952 0.319827 -0.249946 0.897372 0.173093\n8405 39.994520 0.086759 -1.236335 1.318159 0.319657 -0.251690 0.896660 0.174561\n8406 40.003154 0.083553 -1.237722 1.316162 0.319299 -0.254235 0.896012 0.174857\n8407 40.010613 0.080361 -1.238841 1.314215 0.318576 -0.256456 0.895564 0.175229\n8408 40.020573 0.077033 -1.240256 1.312255 0.317276 -0.257171 0.895445 0.177136\n8409 40.028228 0.073676 -1.241558 1.310170 0.317480 -0.261656 0.894461 0.175161\n8410 40.036777 0.070416 -1.242938 1.307687 0.317593 -0.265595 0.892888 0.177042\n8411 40.046216 0.067090 -1.244208 1.305950 0.315581 -0.266282 0.893093 0.178571\n8412 40.052555 0.063419 -1.245596 1.303541 0.315207 -0.270420 0.892065 0.178151\n8413 40.062100 0.060275 -1.247142 1.301787 0.313821 -0.272190 0.891667 0.179884\n8414 40.069666 0.056970 -1.248672 1.299580 0.314642 -0.276144 0.889947 0.180941\n8415 40.077375 0.053211 -1.250086 1.297963 0.312290 -0.278246 0.889582 0.183573\n8416 40.086580 0.050207 -1.251358 1.296015 0.313507 -0.282989 0.887529 0.184185\n8417 40.095285 0.045958 -1.252987 1.293987 0.313701 -0.286179 0.885748 0.187468\n8418 40.102411 0.042187 -1.253862 1.292945 0.311074 -0.289151 0.885416 0.188850\n8419 40.110540 0.038695 -1.255392 1.291885 0.309779 -0.289423 0.885282 0.191175\n8420 40.120749 0.034858 -1.256378 1.290769 0.308406 -0.291398 0.884897 0.192171\n8421 40.128099 0.031126 -1.257292 1.289227 0.307067 -0.293660 0.884349 0.193391\n8422 40.136943 0.027263 -1.257839 1.288755 0.304509 -0.292371 0.885156 0.195686\n8423 40.145295 0.023417 -1.258902 1.288004 0.302159 -0.292572 0.885445 0.197708\n8424 40.152393 0.019390 -1.259468 1.287357 0.298981 -0.291440 0.886390 0.199964\n8425 40.160397 0.015670 -1.259867 1.286721 0.296192 -0.289828 0.887239 0.202675\n8426 40.170668 0.011413 -1.260398 1.286216 0.292579 -0.288224 0.888224 0.205872\n8427 40.178465 0.007049 -1.260980 1.285937 0.288164 -0.286074 0.889437 0.209819\n8428 40.186745 0.003071 -1.261508 1.285290 0.284861 -0.284631 0.890102 0.213443\n8429 40.195326 -0.000895 -1.262076 1.284734 0.281814 -0.282754 0.890703 0.217439\n8430 40.202385 -0.005006 -1.262518 1.284211 0.276961 -0.280559 0.891790 0.222013\n8431 40.210761 -0.009005 -1.262925 1.283380 0.275263 -0.278841 0.891970 0.225539\n8432 40.218898 -0.012883 -1.263412 1.283103 0.270862 -0.275837 0.892939 0.230670\n8433 40.228615 -0.016729 -1.263527 1.282572 0.270500 -0.274149 0.892773 0.233728\n8434 40.237146 -0.020390 -1.263958 1.281690 0.266855 -0.272097 0.893608 0.237100\n8435 40.246668 -0.024727 -1.264131 1.281176 0.261632 -0.268719 0.894951 0.241663\n8436 40.253482 -0.028465 -1.264167 1.280767 0.258584 -0.264891 0.896098 0.244900\n8437 40.260488 -0.032095 -1.263993 1.281076 0.251275 -0.254129 0.900270 0.248581\n8438 40.270364 -0.035437 -1.263853 1.280764 0.248372 -0.253670 0.900537 0.250989\n8439 40.279170 -0.039199 -1.263532 1.280824 0.244172 -0.246506 0.902969 0.253499\n8440 40.286263 -0.042587 -1.262720 1.280747 0.239267 -0.238346 0.905931 0.255405\n8441 40.293672 -0.045913 -1.261900 1.280812 0.234170 -0.228804 0.909113 0.257539\n8442 40.304445 -0.049214 -1.260842 1.280898 0.228046 -0.218439 0.912686 0.259393\n8443 40.311434 -0.052324 -1.259532 1.280898 0.220783 -0.206920 0.916436 0.261887\n8444 40.320097 -0.055479 -1.258120 1.280984 0.214532 -0.196007 0.919903 0.263316\n8445 40.328883 -0.058416 -1.256662 1.280852 0.208930 -0.184362 0.923156 0.264842\n8446 40.335796 -0.061147 -1.255127 1.280909 0.202578 -0.173652 0.925974 0.267167\n8447 40.345091 -0.063804 -1.253592 1.280861 0.196105 -0.162360 0.928832 0.269170\n8448 40.352839 -0.066336 -1.251920 1.281080 0.190520 -0.150887 0.931403 0.270968\n8449 40.360940 -0.068580 -1.250223 1.280751 0.185931 -0.141847 0.933329 0.272409\n8450 40.368939 -0.070665 -1.248544 1.280862 0.182832 -0.132022 0.934858 0.274194\n8451 40.378547 -0.072830 -1.246536 1.280935 0.178145 -0.122145 0.936637 0.275783\n8452 40.386239 -0.074521 -1.244848 1.280477 0.177311 -0.114679 0.937368 0.277040\n8453 40.393896 -0.076290 -1.242580 1.281003 0.173749 -0.105068 0.938606 0.278910\n8454 40.403550 -0.077660 -1.240569 1.281138 0.172894 -0.096659 0.939485 0.279521\n8455 40.410977 -0.078759 -1.238074 1.281254 0.171909 -0.085948 0.940610 0.279844\n8456 40.420013 -0.079991 -1.235961 1.281525 0.171175 -0.077557 0.941281 0.280487\n8457 40.427631 -0.080906 -1.233372 1.281804 0.170054 -0.067333 0.942163 0.280851\n8458 40.435568 -0.081507 -1.230724 1.282078 0.168602 -0.056107 0.942974 0.281469\n8459 40.445109 -0.082629 -1.227896 1.282472 0.166217 -0.044755 0.943977 0.281561\n8460 40.452859 -0.083119 -1.225025 1.282833 0.166349 -0.035769 0.944292 0.281713\n8461 40.460438 -0.083503 -1.222193 1.282899 0.166287 -0.026147 0.944591 0.281802\n8462 40.468999 -0.083895 -1.218968 1.283442 0.165312 -0.016030 0.944867 0.282210\n8463 40.479141 -0.084228 -1.215587 1.283883 0.162660 -0.005827 0.945219 0.282966\n8464 40.486236 -0.084239 -1.212111 1.284185 0.163249 0.003033 0.944865 0.283850\n8465 40.494415 -0.084387 -1.208702 1.284493 0.162579 0.011586 0.945003 0.283555\n8466 40.502852 -0.083994 -1.204973 1.284855 0.161282 0.020295 0.944826 0.284394\n8467 40.510517 -0.084104 -1.201553 1.285064 0.160900 0.028051 0.944764 0.284156\n8468 40.520177 -0.083641 -1.197803 1.285313 0.160426 0.035282 0.944494 0.284516\n8469 40.528759 -0.083496 -1.194215 1.285717 0.158451 0.043417 0.944643 0.284005\n8470 40.536827 -0.083188 -1.190468 1.286030 0.158441 0.051658 0.944468 0.283210\n8471 40.544471 -0.082203 -1.186666 1.286275 0.158730 0.058727 0.944287 0.282272\n8472 40.553424 -0.081824 -1.182889 1.286900 0.155974 0.067504 0.944410 0.281435\n8473 40.562654 -0.080889 -1.178871 1.287309 0.154135 0.077141 0.944364 0.280121\n8474 40.569545 -0.080506 -1.175629 1.287810 0.152971 0.085881 0.944446 0.277932\n8475 40.579213 -0.080037 -1.171468 1.288302 0.151368 0.094860 0.944907 0.274301\n8476 40.586125 -0.079086 -1.167612 1.288872 0.149002 0.104284 0.945041 0.271701\n8477 40.594750 -0.078204 -1.164132 1.289423 0.147857 0.114354 0.945068 0.268158\n8478 40.602113 -0.077413 -1.160264 1.289853 0.144953 0.124168 0.945431 0.264066\n8479 40.611033 -0.076219 -1.156848 1.290358 0.144809 0.133699 0.945292 0.259958\n8480 40.619737 -0.075124 -1.152998 1.291229 0.140829 0.144990 0.945383 0.255726\n8481 40.627212 -0.074520 -1.149528 1.292013 0.137836 0.154221 0.945510 0.251452\n8482 40.637149 -0.073399 -1.145990 1.292992 0.134374 0.162626 0.945771 0.247008\n8483 40.644876 -0.072530 -1.142408 1.293949 0.130410 0.171771 0.945719 0.243111\n8484 40.653493 -0.071512 -1.139058 1.294947 0.127764 0.179678 0.945733 0.238709\n8485 40.662476 -0.069926 -1.136036 1.295915 0.131077 0.186295 0.945059 0.234469\n8486 40.669776 -0.069473 -1.132999 1.296912 0.126994 0.192972 0.945450 0.229692\n8487 40.678876 -0.067643 -1.129834 1.297995 0.123721 0.195476 0.946388 0.225461\n8488 40.686126 -0.067222 -1.127276 1.299038 0.119997 0.202636 0.945922 0.223094\n8489 40.693936 -0.065699 -1.124871 1.300066 0.122666 0.205785 0.946014 0.218320\n8490 40.702792 -0.065096 -1.122383 1.301140 0.119035 0.208446 0.946601 0.215237\n8491 40.710840 -0.063342 -1.119668 1.302153 0.120552 0.211501 0.946544 0.211634\n8492 40.719752 -0.062123 -1.117109 1.303223 0.121091 0.213596 0.946711 0.208453\n8493 40.727276 -0.061009 -1.114648 1.303813 0.128360 0.218870 0.945179 0.205566\n8494 40.736976 -0.059663 -1.111935 1.305032 0.126317 0.221387 0.945502 0.202626\n8495 40.744356 -0.058342 -1.109114 1.306234 0.125560 0.224138 0.945563 0.199769\n8496 40.753496 -0.056895 -1.106180 1.307367 0.122929 0.226771 0.945865 0.196983\n8497 40.760765 -0.055521 -1.103307 1.308515 0.122636 0.230316 0.945484 0.194870\n8498 40.769242 -0.054119 -1.100349 1.309662 0.120314 0.233164 0.945579 0.192458\n8499 40.779123 -0.052479 -1.097460 1.310864 0.118482 0.237402 0.945159 0.190464\n8500 40.786429 -0.050541 -1.094636 1.311983 0.122093 0.241823 0.943958 0.188570\n8501 40.793863 -0.048730 -1.091663 1.312909 0.121171 0.245972 0.943477 0.186187\n8502 40.803950 -0.046657 -1.088670 1.313905 0.123666 0.250096 0.942328 0.184869\n8503 40.811357 -0.044510 -1.085768 1.314767 0.124996 0.254087 0.941477 0.182855\n8504 40.818854 -0.042354 -1.082885 1.315732 0.126503 0.257817 0.940663 0.180777\n8505 40.827335 -0.040226 -1.079967 1.316581 0.128527 0.261307 0.939818 0.178723\n8506 40.836840 -0.037938 -1.077113 1.317350 0.130221 0.264303 0.939158 0.176545\n8507 40.844917 -0.035652 -1.074293 1.317989 0.132685 0.267428 0.938296 0.174580\n8508 40.853493 -0.033318 -1.071407 1.318705 0.134481 0.270046 0.937649 0.172640\n8509 40.861395 -0.030825 -1.068578 1.319445 0.136106 0.272180 0.937164 0.170633\n8510 40.870212 -0.028433 -1.066525 1.319471 0.136389 0.275660 0.936852 0.166485\n8511 40.878603 -0.026092 -1.062695 1.320554 0.133346 0.278635 0.936485 0.166063\n8512 40.886418 -0.023613 -1.060016 1.320933 0.138870 0.283578 0.934750 0.162912\n8513 40.894236 -0.020846 -1.056882 1.321802 0.133983 0.286313 0.934984 0.160868\n8514 40.902296 -0.018263 -1.053874 1.322122 0.138988 0.292747 0.932786 0.157770\n8515 40.912055 -0.015492 -1.050865 1.322453 0.140261 0.296984 0.931938 0.153687\n8516 40.919652 -0.012298 -1.048217 1.323233 0.140005 0.298917 0.931866 0.150576\n8517 40.927405 -0.009439 -1.045317 1.323739 0.140470 0.302760 0.931037 0.147565\n8518 40.936252 -0.006094 -1.042727 1.324291 0.139722 0.305898 0.930762 0.143478\n8519 40.943930 -0.003344 -1.039525 1.324587 0.144368 0.309748 0.929302 0.140047\n8520 40.954011 -0.000433 -1.036863 1.325224 0.141519 0.312095 0.929367 0.137279\n8521 40.961263 0.002525 -1.034056 1.325531 0.147309 0.317434 0.927291 0.132917\n8522 40.968824 0.006010 -1.031545 1.325908 0.146197 0.318286 0.927594 0.129960\n8523 40.978221 0.009280 -1.028992 1.326198 0.149149 0.321951 0.926129 0.128012\n8524 40.986747 0.012089 -1.026689 1.326382 0.150201 0.322647 0.925796 0.127438\n8525 40.993945 0.015334 -1.024184 1.326619 0.152397 0.325584 0.924626 0.125849\n8526 41.003967 0.018673 -1.021780 1.326737 0.156152 0.327693 0.923341 0.125200\n8527 41.011811 0.022293 -1.019315 1.326989 0.158988 0.328946 0.922640 0.123503\n8528 41.020110 0.025489 -1.017164 1.327621 0.162421 0.332430 0.920711 0.124099\n8529 41.029221 0.028833 -1.014517 1.327415 0.161705 0.333431 0.920392 0.124717\n8530 41.036191 0.032285 -1.012166 1.327689 0.165326 0.335357 0.918964 0.125331\n8531 41.050485 0.035160 -1.009887 1.327904 0.168592 0.338182 0.917251 0.125942\n8532 41.052919 0.039488 -1.007616 1.327848 0.173162 0.338116 0.916123 0.128105\n8533 41.060814 0.042496 -1.005291 1.328083 0.174889 0.340428 0.914773 0.129283\n8534 41.070283 0.045680 -1.003166 1.328201 0.176837 0.341547 0.913784 0.130667\n8535 41.077799 0.049230 -1.000936 1.328133 0.179972 0.343096 0.912414 0.131892\n8536 41.086778 0.052129 -0.998973 1.328404 0.183691 0.343615 0.911249 0.133460\n8537 41.096139 0.055791 -0.996080 1.328402 0.186018 0.343980 0.910178 0.136569\n8538 41.102421 0.059505 -0.993136 1.328363 0.188755 0.344230 0.909071 0.139526\n8539 41.110590 0.062027 -0.990795 1.328873 0.188356 0.344261 0.908664 0.142605\n8540 41.120077 0.065964 -0.988337 1.328386 0.194145 0.344745 0.906790 0.145568\n8541 41.127712 0.069982 -0.985534 1.328833 0.199117 0.350369 0.903240 0.147484\n8542 41.136588 0.071108 -0.981483 1.328737 0.200630 0.343436 0.905431 0.148303\n8543 41.145866 0.075467 -0.980011 1.328539 0.199222 0.348373 0.902575 0.155903\n8544 41.152553 0.078326 -0.977645 1.328607 0.203068 0.346307 0.901839 0.159753\n8545 41.162445 0.081848 -0.975003 1.328637 0.207715 0.344182 0.900555 0.165513\n8546 41.170098 0.085024 -0.972795 1.328523 0.210034 0.343393 0.899334 0.170777\n8547 41.178023 0.088316 -0.970380 1.328312 0.212115 0.342519 0.898055 0.176594\n8548 41.186441 0.091378 -0.968275 1.328197 0.215494 0.340650 0.896782 0.182486\n8549 41.194488 0.094676 -0.965795 1.327881 0.218175 0.340720 0.895285 0.186478\n8550 41.203397 0.097984 -0.963328 1.327603 0.218286 0.339583 0.893596 0.196266\n8551 41.210287 0.101184 -0.961174 1.327348 0.220280 0.338744 0.891707 0.203931\n8552 41.220013 0.104327 -0.958521 1.326693 0.225939 0.338916 0.888631 0.210766\n8553 41.227434 0.108375 -0.957005 1.326073 0.228627 0.339108 0.885797 0.219315\n8554 41.235899 0.111166 -0.955302 1.326244 0.231863 0.337370 0.883373 0.228196\n8555 41.245862 0.113970 -0.953399 1.325775 0.234705 0.333798 0.881914 0.236050\n8556 41.253338 0.116966 -0.951007 1.325195 0.234763 0.332011 0.879993 0.245495\n8557 41.260561 0.120282 -0.949364 1.324952 0.237694 0.328569 0.877618 0.255600\n8558 41.270481 0.122757 -0.947787 1.324613 0.239808 0.325253 0.875770 0.264062\n8559 41.278178 0.126788 -0.946282 1.324408 0.240973 0.322379 0.872987 0.275494\n8560 41.286804 0.129380 -0.945018 1.323817 0.243793 0.319541 0.870300 0.284669\n8561 41.296386 0.132606 -0.943397 1.323285 0.246424 0.316882 0.867539 0.293662\n8562 41.303070 0.135314 -0.942116 1.323087 0.246553 0.314953 0.864625 0.304039\n8563 41.312425 0.138153 -0.941177 1.322880 0.246544 0.311611 0.862945 0.312155\n8564 41.319515 0.141789 -0.939418 1.321798 0.251776 0.309610 0.858295 0.322615\n8565 41.327387 0.143852 -0.938662 1.321731 0.250570 0.304970 0.857676 0.329546\n8566 41.337240 0.146714 -0.937570 1.321209 0.252908 0.299755 0.855125 0.339036\n8567 41.344286 0.149107 -0.936820 1.320965 0.249252 0.294539 0.854812 0.347012\n8568 41.353159 0.151850 -0.935908 1.320442 0.251494 0.288494 0.852345 0.356412\n8569 41.363105 0.153932 -0.935113 1.319968 0.252511 0.282320 0.851038 0.363687\n8570 41.369867 0.156338 -0.934576 1.319659 0.249593 0.277092 0.850365 0.371217\n8571 41.377177 0.158682 -0.934156 1.319316 0.251153 0.270549 0.848123 0.380017\n8572 41.386921 0.160371 -0.933753 1.319149 0.247362 0.265666 0.847720 0.386786\n8573 41.395408 0.162282 -0.933094 1.318698 0.247111 0.259334 0.847076 0.392613\n8574 41.403557 0.164085 -0.932755 1.318551 0.245137 0.253483 0.846404 0.399066\n8575 41.412335 0.165834 -0.931782 1.317950 0.246146 0.248230 0.845640 0.403344\n8576 41.420288 0.167668 -0.932358 1.317231 0.247845 0.242183 0.844708 0.407907\n8577 41.428424 0.169623 -0.931831 1.316602 0.251076 0.236468 0.843683 0.411390\n8578 41.436376 0.170662 -0.931960 1.317396 0.244709 0.234060 0.843497 0.416949\n8579 41.444474 0.171075 -0.931751 1.316881 0.244789 0.231078 0.843184 0.419193\n8580 41.453223 0.173535 -0.931069 1.316598 0.244578 0.226856 0.842548 0.422883\n8581 41.462418 0.175445 -0.931572 1.316206 0.247080 0.222268 0.843241 0.422485\n8582 41.470052 0.176829 -0.931567 1.315825 0.246996 0.217873 0.843526 0.424250\n8583 41.478840 0.178569 -0.931369 1.315708 0.249495 0.212916 0.842586 0.427162\n8584 41.487126 0.179287 -0.931564 1.315247 0.247659 0.207489 0.843548 0.428999\n8585 41.495341 0.180235 -0.931901 1.314989 0.247295 0.200760 0.844634 0.430271\n8586 41.503333 0.180828 -0.932486 1.314645 0.247669 0.192296 0.845514 0.432191\n8587 41.511350 0.181818 -0.932816 1.314575 0.248711 0.185073 0.846026 0.433740\n8588 41.518613 0.182010 -0.933504 1.314288 0.247417 0.176784 0.847054 0.435927\n8589 41.527459 0.182266 -0.934199 1.314017 0.246583 0.168812 0.848219 0.437292\n8590 41.538687 0.182373 -0.934917 1.313789 0.245668 0.160687 0.849448 0.438481\n8591 41.545142 0.182402 -0.935655 1.313529 0.244631 0.152708 0.850770 0.439348\n8592 41.553323 0.182195 -0.936427 1.313227 0.243634 0.145281 0.852191 0.439666\n8593 41.562087 0.181851 -0.937175 1.312765 0.243557 0.137527 0.853556 0.439555\n8594 41.570316 0.181938 -0.938586 1.313262 0.237354 0.128098 0.855838 0.441357\n8595 41.579708 0.181640 -0.940264 1.312599 0.231680 0.122329 0.858483 0.440872\n8596 41.587060 0.181132 -0.940013 1.312748 0.231487 0.114463 0.859722 0.440671\n8597 41.593904 0.180680 -0.941075 1.312487 0.231539 0.107310 0.861585 0.438800\n8598 41.603164 0.180223 -0.942690 1.312254 0.226933 0.100719 0.864049 0.437923\n8599 41.613169 0.179850 -0.944066 1.312018 0.223332 0.092989 0.866134 0.437366\n8600 41.620133 0.178856 -0.945481 1.311617 0.219431 0.085301 0.868575 0.436063\n8601 41.629218 0.178060 -0.946368 1.311440 0.216733 0.077606 0.870375 0.435261\n8602 41.636713 0.177285 -0.947626 1.310731 0.210688 0.070444 0.873651 0.432877\n8603 41.644368 0.175203 -0.949275 1.310899 0.205744 0.063517 0.874993 0.433616\n8604 41.652184 0.174768 -0.950826 1.310488 0.202587 0.054066 0.877625 0.431057\n8605 41.661069 0.173898 -0.952165 1.309948 0.200322 0.044901 0.880333 0.427632\n8606 41.670055 0.172753 -0.953781 1.309479 0.195851 0.036677 0.883576 0.423782\n8607 41.677343 0.171452 -0.955521 1.309253 0.195223 0.026959 0.886082 0.419546\n8608 41.685534 0.170139 -0.957285 1.308753 0.191178 0.018315 0.889091 0.415492\n8609 41.694877 0.169078 -0.959266 1.308311 0.188261 0.008583 0.891770 0.411376\n8610 41.703492 0.167988 -0.960789 1.307808 0.184353 -0.000810 0.894990 0.406211\n8611 41.712021 0.167077 -0.962670 1.307316 0.183107 -0.011670 0.897584 0.400847\n8612 41.720381 0.166055 -0.964540 1.306733 0.180713 -0.021994 0.900438 0.395058\n8613 41.727689 0.164994 -0.966534 1.306129 0.178804 -0.032060 0.903228 0.388819\n8614 41.737684 0.163904 -0.968518 1.305469 0.177241 -0.041935 0.906046 0.381977\n8615 41.744768 0.162847 -0.970626 1.304778 0.175793 -0.051807 0.908777 0.374884\n8616 41.753037 0.161076 -0.972472 1.304060 0.171338 -0.060291 0.912038 0.367689\n8617 41.761313 0.160053 -0.974801 1.303294 0.171276 -0.069454 0.914768 0.359222\n8618 41.770349 0.158998 -0.977224 1.302470 0.170771 -0.077947 0.917378 0.350970\n8619 41.778483 0.157800 -0.979544 1.301532 0.169318 -0.086550 0.920015 0.342655\n8620 41.786504 0.156556 -0.981817 1.300645 0.167605 -0.094402 0.922563 0.334475\n8621 41.794363 0.155153 -0.983860 1.299860 0.163861 -0.101813 0.925426 0.326146\n8622 41.802072 0.153902 -0.986001 1.298823 0.160078 -0.109414 0.928075 0.317933\n8623 41.811626 0.152774 -0.987921 1.297843 0.156238 -0.118061 0.930542 0.309422\n8624 41.819976 0.151341 -0.990370 1.296839 0.152436 -0.126537 0.932621 0.301613\n8625 41.827307 0.149678 -0.992161 1.295876 0.148030 -0.134388 0.935012 0.292882\n8626 41.835517 0.148466 -0.994177 1.294849 0.143171 -0.142507 0.936813 0.285614\n8627 41.845413 0.147236 -0.996087 1.293986 0.139079 -0.151344 0.938501 0.277433\n8628 41.853623 0.145865 -0.998367 1.292946 0.135051 -0.159834 0.939766 0.270285\n8629 41.860715 0.144747 -1.000435 1.291935 0.132071 -0.167381 0.940764 0.263637\n8630 41.869698 0.143843 -1.002592 1.290893 0.130466 -0.176026 0.941217 0.257109\n8631 41.878103 0.142730 -1.004833 1.289869 0.127680 -0.182326 0.942097 0.250817\n8632 41.887012 0.142002 -1.006983 1.288783 0.128435 -0.190418 0.941819 0.245403\n8633 41.895765 0.141071 -1.009105 1.287847 0.127691 -0.196343 0.942094 0.240006\n8634 41.902811 0.140500 -1.011261 1.286736 0.129881 -0.203772 0.941588 0.234565\n8635 41.910903 0.139632 -1.013295 1.285715 0.130781 -0.209217 0.941518 0.229497\n8636 41.919541 0.138961 -1.015225 1.284626 0.132136 -0.215182 0.941101 0.224865\n8637 41.928227 0.138309 -1.016958 1.283700 0.132370 -0.220009 0.940940 0.220695\n8638 41.936829 0.137150 -1.018864 1.282775 0.131252 -0.224184 0.941174 0.216115\n8639 41.944008 0.136732 -1.020634 1.281708 0.132284 -0.230365 0.940370 0.212458\n8640 41.953576 0.136029 -1.022223 1.280731 0.131707 -0.234552 0.940084 0.209477\n8641 41.960889 0.135355 -1.023280 1.279766 0.131129 -0.238805 0.940040 0.205187\n8642 41.970110 0.134426 -1.024972 1.279172 0.128422 -0.241487 0.940150 0.203250\n8643 41.978296 0.134040 -1.026394 1.278170 0.128812 -0.245160 0.939680 0.200762\n8644 41.986836 0.133334 -1.027421 1.277545 0.126936 -0.247675 0.939618 0.199157\n8645 41.994976 0.132750 -1.028559 1.276853 0.126118 -0.249562 0.939511 0.197817\n8646 42.004272 0.132319 -1.029513 1.276171 0.125323 -0.251367 0.939326 0.196915\n8647 42.012110 0.131889 -1.030371 1.275584 0.124428 -0.252183 0.939327 0.196435\n8648 42.019487 0.131621 -1.031108 1.275103 0.124629 -0.253241 0.939091 0.196073\n8649 42.028562 0.131148 -1.031902 1.274659 0.124317 -0.252692 0.939186 0.196522\n8650 42.036298 0.130781 -1.032367 1.274415 0.124008 -0.251959 0.939364 0.196808\n8651 42.045896 0.130390 -1.032850 1.274168 0.124480 -0.250030 0.939530 0.198176\n8652 42.053493 0.130389 -1.033230 1.273910 0.126602 -0.248719 0.939259 0.199757\n8653 42.061928 0.130010 -1.033405 1.273899 0.127117 -0.245253 0.939647 0.201879\n8654 42.070176 0.130198 -1.033521 1.273748 0.129360 -0.242335 0.939388 0.205157\n8655 42.077591 0.130139 -1.033405 1.273833 0.130458 -0.238238 0.939493 0.208750\n8656 42.086685 0.129742 -1.033405 1.273956 0.131090 -0.233364 0.939726 0.212772\n8657 42.094882 0.129793 -1.033201 1.274117 0.131559 -0.227819 0.939992 0.217268\n8658 42.103669 0.130196 -1.032844 1.274277 0.133883 -0.222944 0.939582 0.222613\n8659 42.111302 0.130413 -1.032455 1.274370 0.134945 -0.216458 0.939574 0.228334\n8660 42.119889 0.130533 -1.031816 1.274866 0.135244 -0.208869 0.940019 0.233337\n8661 42.127584 0.130508 -1.031217 1.275293 0.134230 -0.199175 0.940900 0.238785\n8662 42.136723 0.130975 -1.030522 1.275648 0.135283 -0.190637 0.941199 0.243927\n8663 42.144529 0.131117 -1.029729 1.276067 0.135402 -0.181141 0.941788 0.248776\n8664 42.153378 0.131433 -1.029384 1.276201 0.136631 -0.171333 0.942168 0.253566\n8665 42.161943 0.131853 -1.028676 1.276633 0.137307 -0.161522 0.942605 0.257980\n8666 42.170160 0.132086 -1.027030 1.277329 0.137080 -0.150397 0.943330 0.262143\n8667 42.178951 0.132718 -1.026178 1.277814 0.139015 -0.140889 0.943486 0.265818\n8668 42.186592 0.132813 -1.025239 1.278274 0.139600 -0.130565 0.943776 0.269724\n8669 42.194550 0.133354 -1.024274 1.278793 0.140914 -0.120574 0.943658 0.274072\n8670 42.203461 0.133803 -1.023209 1.279278 0.142243 -0.110701 0.943412 0.278362\n8671 42.211665 0.134270 -1.022151 1.279709 0.143802 -0.100871 0.942996 0.282674\n8672 42.218683 0.134773 -1.020936 1.280207 0.144639 -0.090354 0.942542 0.287281\n8673 42.227609 0.134992 -1.019892 1.280675 0.145847 -0.080286 0.941956 0.291551\n8674 42.236117 0.135451 -1.019163 1.280900 0.147647 -0.071762 0.940940 0.296112\n8675 42.244202 0.135865 -1.018133 1.281396 0.149296 -0.062849 0.940036 0.300154\n8676 42.253389 0.136106 -1.016968 1.281854 0.148661 -0.053334 0.939319 0.304526\n8677 42.261230 0.136490 -1.015893 1.282288 0.149614 -0.044599 0.938214 0.308838\n8678 42.268850 0.136865 -1.014859 1.282631 0.151868 -0.035648 0.936987 0.312603\n8679 42.277190 0.137098 -1.013793 1.283145 0.152139 -0.025859 0.935944 0.316534\n8680 42.286768 0.136986 -1.012464 1.283596 0.152483 -0.015324 0.935027 0.319749\n8681 42.296229 0.137390 -1.011366 1.284166 0.152596 -0.005714 0.933797 0.323583\n8682 42.303360 0.137382 -1.009915 1.284717 0.152888 0.005021 0.932596 0.326902\n8683 42.312268 0.137401 -1.009091 1.285118 0.153281 0.015259 0.931288 0.330113\n8684 42.320190 0.137573 -1.007987 1.285556 0.153375 0.025565 0.929773 0.333684\n8685 42.328589 0.137418 -1.006444 1.286289 0.152912 0.036060 0.928670 0.335992\n8686 42.337192 0.137500 -1.005603 1.286702 0.149726 0.045090 0.927072 0.340715\n8687 42.344560 0.137928 -1.004784 1.287130 0.154286 0.055597 0.924626 0.343761\n8688 42.353117 0.137959 -1.003663 1.287561 0.153851 0.065185 0.922826 0.347091\n8689 42.362999 0.138035 -1.002536 1.287990 0.153297 0.074135 0.920977 0.350436\n8690 42.370236 0.138166 -1.001473 1.288366 0.152670 0.082708 0.919052 0.353829\n8691 42.378341 0.138279 -1.000424 1.288728 0.152050 0.090805 0.917051 0.357285\n8692 42.386298 0.138331 -0.999353 1.289108 0.151561 0.098751 0.915023 0.360570\n8693 42.394088 0.138399 -0.998261 1.289559 0.150840 0.106745 0.912992 0.363729\n8694 42.403358 0.138429 -0.997085 1.289966 0.150527 0.114604 0.910839 0.366851\n8695 42.411427 0.138376 -0.995613 1.290337 0.149888 0.122859 0.908714 0.369699\n8696 42.420015 0.138343 -0.994407 1.290666 0.149442 0.131142 0.906436 0.372617\n8697 42.429090 0.138240 -0.993077 1.291118 0.148888 0.139559 0.904163 0.375293\n8698 42.436431 0.138150 -0.991760 1.291455 0.148077 0.147982 0.901913 0.377793\n8699 42.445303 0.138232 -0.990578 1.291844 0.146943 0.156470 0.899538 0.380469\n8700 42.453619 0.138085 -0.989255 1.292185 0.146280 0.164990 0.897140 0.382780\n8701 42.461122 0.138183 -0.988250 1.292548 0.143210 0.174187 0.895003 0.384863\n8702 42.470212 0.137999 -0.986801 1.293088 0.138992 0.183688 0.893000 0.386640\n8703 42.477854 0.137865 -0.985409 1.293256 0.138670 0.193731 0.889810 0.389200\n8704 42.486690 0.137948 -0.984481 1.293610 0.138423 0.203988 0.887046 0.390356\n8705 42.494790 0.137611 -0.983231 1.293583 0.136791 0.215099 0.884344 0.391097\n8706 42.503535 0.137595 -0.982356 1.294074 0.137858 0.225087 0.880908 0.392851\n8707 42.512305 0.137140 -0.980443 1.294236 0.130958 0.239288 0.878186 0.392914\n8708 42.520087 0.136740 -0.979600 1.294430 0.132374 0.247584 0.874902 0.394620\n8709 42.527532 0.136603 -0.978400 1.294752 0.131498 0.257994 0.871955 0.394768\n8710 42.538028 0.136380 -0.977524 1.294917 0.125163 0.269814 0.869906 0.393443\n8711 42.545328 0.135660 -0.975702 1.295212 0.119491 0.282079 0.866470 0.394188\n8712 42.552887 0.135382 -0.974793 1.295021 0.117638 0.291457 0.863634 0.394146\n8713 42.562278 0.134837 -0.973035 1.295599 0.111660 0.303453 0.860353 0.394007\n8714 42.569741 0.134365 -0.971712 1.295511 0.107762 0.311890 0.857244 0.395277\n8715 42.577721 0.134160 -0.970280 1.295421 0.102637 0.322200 0.853821 0.395782\n8716 42.586610 0.133270 -0.968947 1.295980 0.092114 0.333269 0.851873 0.393394\n8717 42.594581 0.132789 -0.967700 1.296032 0.088173 0.341891 0.848663 0.393837\n8718 42.603659 0.132168 -0.966513 1.296030 0.082342 0.349983 0.846716 0.392179\n8719 42.611564 0.131148 -0.965190 1.295952 0.077951 0.358747 0.843716 0.391623\n8720 42.620207 0.130730 -0.963947 1.296054 0.070255 0.366875 0.842029 0.389171\n8721 42.628688 0.130359 -0.962568 1.296122 0.064148 0.374888 0.840379 0.386144\n8722 42.636532 0.129939 -0.961081 1.296380 0.055677 0.382820 0.838996 0.382667\n8723 42.644713 0.127545 -0.959505 1.295563 0.053583 0.388887 0.836228 0.382908\n8724 42.653346 0.129132 -0.958777 1.296328 0.052418 0.394148 0.836244 0.377620\n8725 42.661556 0.128344 -0.957506 1.296499 0.046210 0.401915 0.835365 0.372149\n8726 42.670650 0.127394 -0.956662 1.296441 0.039727 0.409288 0.834843 0.365980\n8727 42.677894 0.127316 -0.955208 1.296605 0.037303 0.413699 0.835006 0.360870\n8728 42.686392 0.126652 -0.954564 1.296858 0.035182 0.419844 0.833928 0.356451\n8729 42.695353 0.126065 -0.953606 1.296936 0.033543 0.424415 0.833778 0.351512\n8730 42.702175 0.125363 -0.952699 1.297125 0.031437 0.429442 0.833932 0.345179\n8731 42.711226 0.125018 -0.951909 1.297494 0.029125 0.431334 0.835226 0.339853\n8732 42.719977 0.124386 -0.951072 1.297938 0.026747 0.434837 0.836338 0.332777\n8733 42.728836 0.123814 -0.950484 1.298097 0.024078 0.435964 0.838448 0.326130\n8734 42.736829 0.122952 -0.949884 1.298610 0.023909 0.438521 0.839715 0.319384\n8735 42.744439 0.122192 -0.949540 1.299083 0.022675 0.438094 0.842525 0.312588\n8736 42.753425 0.121211 -0.949198 1.299409 0.021392 0.438070 0.845144 0.305563\n8737 42.761562 0.120293 -0.949143 1.299693 0.022414 0.436212 0.848275 0.299412\n8738 42.768654 0.119171 -0.948757 1.300166 0.018660 0.436054 0.851258 0.291324\n8739 42.778110 0.118334 -0.948545 1.300822 0.019668 0.434855 0.853958 0.285079\n8740 42.785987 0.116984 -0.947978 1.301373 0.015897 0.434063 0.857392 0.276070\n8741 42.793988 0.116651 -0.947342 1.302266 0.010177 0.433750 0.860169 0.268079\n8742 42.804418 0.114541 -0.947873 1.302031 0.013370 0.430894 0.863722 0.261029\n8743 42.811537 0.113208 -0.947374 1.302782 0.007831 0.430546 0.865452 0.256050\n8744 42.818507 0.111814 -0.947181 1.302603 0.006510 0.429639 0.868543 0.246982\n8745 42.828178 0.110692 -0.947867 1.303351 0.004729 0.427330 0.872410 0.237209\n8746 42.836737 0.109541 -0.948142 1.303979 0.001456 0.425637 0.875273 0.229626\n8747 42.844324 0.108518 -0.948500 1.304493 0.000734 0.422284 0.878663 0.222771\n8748 42.853316 0.106935 -0.948856 1.304521 -0.003959 0.419316 0.882295 0.213809\n8749 42.861309 0.105477 -0.949770 1.305698 -0.005587 0.417457 0.885055 0.205854\n8750 42.868643 0.104534 -0.949984 1.305650 -0.011326 0.412328 0.889561 0.196312\n8751 42.878623 0.102964 -0.950679 1.306180 -0.013153 0.408351 0.893359 0.187047\n8752 42.886041 0.101166 -0.951147 1.306646 -0.013019 0.403427 0.897397 0.178203\n8753 42.894167 0.099971 -0.952024 1.306854 -0.016767 0.397123 0.902037 0.168350\n8754 42.903979 0.098174 -0.952828 1.306899 -0.022163 0.391161 0.906082 0.159743\n8755 42.912131 0.096990 -0.953718 1.308069 -0.021691 0.384920 0.910554 0.149191\n8756 42.920137 0.095557 -0.954829 1.308273 -0.023770 0.378085 0.914893 0.139491\n8757 42.928675 0.094034 -0.955906 1.308682 -0.026186 0.372081 0.918702 0.129830\n8758 42.936579 0.092639 -0.957118 1.309001 -0.028794 0.366143 0.922373 0.119740\n8759 42.944336 0.091244 -0.958495 1.309201 -0.032291 0.360501 0.925752 0.109447\n8760 42.953450 0.090152 -0.959891 1.309505 -0.034369 0.355413 0.928672 0.100338\n8761 42.961579 0.088642 -0.961389 1.309374 -0.037623 0.350776 0.931361 0.090046\n8762 42.970125 0.087429 -0.962632 1.309923 -0.041031 0.344521 0.934358 0.081222\n8763 42.978701 0.085808 -0.963777 1.310064 -0.050425 0.338278 0.936946 0.071814\n8764 42.986722 0.084070 -0.965296 1.309956 -0.053083 0.333419 0.939182 0.062855\n8765 42.995239 0.083105 -0.966541 1.310023 -0.053048 0.328056 0.941579 0.054723\n8766 43.003512 0.081847 -0.967924 1.309871 -0.052702 0.322603 0.943934 0.046254\n8767 43.010850 0.080496 -0.969171 1.309714 -0.057434 0.318057 0.945561 0.038147\n8768 43.020173 0.079772 -0.970730 1.310103 -0.059119 0.307772 0.949180 0.028946\n8769 43.028210 0.077774 -0.972404 1.310365 -0.062972 0.305388 0.949855 0.023395\n8770 43.035295 0.076272 -0.974016 1.310768 -0.065806 0.298494 0.952041 0.013760\n8771 43.044038 0.075175 -0.975648 1.310815 -0.068653 0.290444 0.954398 0.007274\n8772 43.053507 0.074317 -0.978242 1.310739 -0.067566 0.284269 0.956357 0.002796\n8773 43.060789 0.073383 -0.979354 1.310337 -0.067321 0.274053 0.959354 -0.001994\n8774 43.070714 0.072191 -0.980338 1.309898 -0.071963 0.267748 0.960784 -0.005081\n8775 43.077828 0.071766 -0.983214 1.310418 -0.068484 0.257350 0.963846 -0.009103\n8776 43.087248 0.071369 -0.985232 1.310198 -0.067331 0.248660 0.966181 -0.011364\n8777 43.095439 0.070407 -0.986996 1.309803 -0.065764 0.241465 0.968100 -0.012354\n8778 43.103348 0.069661 -0.988783 1.309515 -0.065272 0.233561 0.970064 -0.012813\n8779 43.112078 0.068880 -0.990551 1.309225 -0.063326 0.225818 0.972030 -0.012405\n8780 43.119703 0.067566 -0.992036 1.309098 -0.069023 0.217600 0.973532 -0.011045\n8781 43.127327 0.066759 -0.993670 1.308664 -0.064543 0.210458 0.975427 -0.009134\n8782 43.136362 0.065891 -0.995275 1.308230 -0.062460 0.204305 0.976887 -0.007099\n8783 43.145326 0.065005 -0.996868 1.307819 -0.058438 0.197855 0.978479 -0.004210\n8784 43.153858 0.064445 -0.998850 1.307414 -0.051394 0.192385 0.979972 -0.000921\n8785 43.160910 0.063445 -1.000457 1.307029 -0.048941 0.186372 0.981254 0.003227\n8786 43.170114 0.062188 -1.002252 1.306781 -0.049695 0.180643 0.982267 0.007025\n8787 43.178292 0.061531 -1.004246 1.306547 -0.046636 0.176082 0.983194 0.012210\n8788 43.185407 0.060450 -1.006101 1.306089 -0.044197 0.172049 0.983944 0.017338\n8789 43.193788 0.059378 -1.007996 1.305418 -0.043292 0.168288 0.984537 0.022190\n8790 43.202906 0.058553 -1.009757 1.305067 -0.042817 0.163676 0.985168 0.028653\n8791 43.210793 0.058023 -1.012586 1.304816 -0.044686 0.160246 0.985489 0.033697\n8792 43.220884 0.055918 -1.013681 1.304000 -0.049863 0.157473 0.985430 0.040538\n8793 43.227625 0.055097 -1.015847 1.303398 -0.048464 0.153606 0.985836 0.046731\n8794 43.235423 0.053705 -1.017812 1.302596 -0.051062 0.150693 0.985830 0.053135\n8795 43.244176 0.052561 -1.019878 1.301868 -0.052680 0.146643 0.986007 0.059256\n8796 43.252992 0.051627 -1.022590 1.301020 -0.048892 0.143945 0.986164 0.066103\n8797 43.260895 0.050705 -1.024395 1.300101 -0.052283 0.141267 0.985958 0.072094\n8798 43.270691 0.049161 -1.026465 1.299250 -0.051668 0.139072 0.985872 0.077754\n8799 43.278177 0.047661 -1.028990 1.298387 -0.053788 0.137255 0.985493 0.084095\n8800 43.287292 0.046240 -1.031135 1.297444 -0.058073 0.134544 0.985126 0.089731\n8801 43.295539 0.045417 -1.033428 1.296178 -0.054793 0.133439 0.984888 0.095855\n8802 43.303366 0.043415 -1.035664 1.295178 -0.060921 0.131982 0.984173 0.101358\n8803 43.311794 0.042310 -1.038137 1.294026 -0.060706 0.130822 0.983736 0.107069\n8804 43.319389 0.041380 -1.041242 1.293006 -0.057945 0.129526 0.983419 0.112923\n8805 43.328829 0.039834 -1.043479 1.291500 -0.062564 0.130097 0.982593 0.116924\n8806 43.336593 0.038257 -1.046008 1.290337 -0.059946 0.127154 0.982375 0.123196\n8807 43.344481 0.037650 -1.048834 1.288978 -0.053988 0.126435 0.982131 0.128522\n8808 43.352039 0.036017 -1.051290 1.287500 -0.057811 0.124917 0.981471 0.133298\n8809 43.362238 0.034997 -1.054613 1.286102 -0.054359 0.124187 0.980967 0.139023\n8810 43.370915 0.033869 -1.057279 1.284588 -0.053765 0.122724 0.980392 0.144499\n8811 43.379831 0.031969 -1.059617 1.282850 -0.054877 0.121527 0.979869 0.148584\n8812 43.386836 0.030809 -1.062371 1.281205 -0.054018 0.120516 0.979298 0.153404\n8813 43.394583 0.029482 -1.065272 1.279556 -0.053102 0.119297 0.978726 0.158253\n8814 43.404032 0.028230 -1.068230 1.277955 -0.051507 0.117700 0.978288 0.162621\n8815 43.412201 0.026565 -1.071095 1.276229 -0.049897 0.116566 0.977682 0.167516\n8816 43.420084 0.025539 -1.074144 1.274580 -0.048474 0.115284 0.977224 0.171442\n8817 43.429717 0.024215 -1.077210 1.272665 -0.043557 0.115310 0.976672 0.175838\n8818 43.436937 0.022470 -1.079883 1.271051 -0.046519 0.113276 0.976150 0.179264\n8819 43.446073 0.021077 -1.082663 1.269060 -0.041995 0.113488 0.975565 0.183385\n8820 43.453377 0.019523 -1.085358 1.267484 -0.041174 0.112768 0.975045 0.186748\n8821 43.461607 0.018268 -1.088341 1.265693 -0.042096 0.110190 0.974599 0.190374\n8822 43.469623 0.016026 -1.091373 1.264145 -0.041946 0.108563 0.974268 0.193020\n8823 43.479025 0.014424 -1.093807 1.262198 -0.039167 0.107966 0.973929 0.195631\n8824 43.487005 0.012613 -1.096413 1.260507 -0.039354 0.106535 0.973479 0.198598\n8825 43.495173 0.010350 -1.098486 1.258646 -0.043783 0.106321 0.972874 0.200736\n8826 43.503375 0.009015 -1.101303 1.256935 -0.038652 0.103422 0.972846 0.203423\n8827 43.511101 0.007292 -1.103880 1.255264 -0.038719 0.103339 0.971986 0.207519\n8828 43.520116 0.004811 -1.106475 1.253349 -0.039592 0.100930 0.971765 0.209568\n8829 43.528508 0.003653 -1.108207 1.251254 -0.040900 0.100287 0.971161 0.212404\n8830 43.536658 0.001996 -1.110976 1.249704 -0.037145 0.098692 0.970997 0.214581\n8831 43.543916 -0.000411 -1.113341 1.247805 -0.040578 0.097769 0.970496 0.216637\n8832 43.553399 -0.001775 -1.116134 1.246006 -0.037572 0.097447 0.969954 0.219732\n8833 43.561341 -0.003874 -1.118350 1.244217 -0.035610 0.097071 0.969496 0.222230\n8834 43.570005 -0.006346 -1.120949 1.242259 -0.038609 0.095497 0.969253 0.223469\n8835 43.577775 -0.008638 -1.123248 1.240219 -0.038963 0.095106 0.968690 0.225999\n8836 43.586300 -0.010188 -1.126040 1.238383 -0.035004 0.092873 0.968452 0.228584\n8837 43.594740 -0.012132 -1.128825 1.236229 -0.033332 0.091595 0.968163 0.230562\n8838 43.603419 -0.014309 -1.131083 1.234223 -0.034090 0.089989 0.967637 0.233277\n8839 43.611992 -0.016182 -1.133833 1.232276 -0.032859 0.088297 0.967164 0.236045\n8840 43.619979 -0.018733 -1.136092 1.230236 -0.035621 0.087079 0.966817 0.237517\n8841 43.628067 -0.020864 -1.138830 1.228182 -0.034681 0.085363 0.966356 0.240139\n8842 43.635514 -0.022912 -1.141382 1.226047 -0.031348 0.083829 0.966001 0.242554\n8843 43.647491 -0.025208 -1.144045 1.223923 -0.031259 0.082498 0.965439 0.245243\n8844 43.652494 -0.027423 -1.146467 1.221395 -0.029303 0.080280 0.965217 0.247090\n8845 43.660770 -0.029968 -1.148900 1.219573 -0.033744 0.080248 0.964238 0.250335\n8846 43.670145 -0.032068 -1.151810 1.217326 -0.028860 0.078362 0.963897 0.252843\n8847 43.678255 -0.034558 -1.154299 1.214973 -0.027967 0.078479 0.962971 0.256409\n8848 43.685421 -0.036505 -1.157522 1.212952 -0.028856 0.075762 0.962200 0.259997\n8849 43.695570 -0.039345 -1.159297 1.210453 -0.030450 0.076138 0.961373 0.262750\n8850 43.703411 -0.041245 -1.162053 1.208187 -0.027128 0.073451 0.960949 0.265416\n8851 43.711475 -0.044299 -1.164639 1.205672 -0.028214 0.073278 0.959696 0.269850\n8852 43.720147 -0.046629 -1.167359 1.203394 -0.027437 0.071938 0.959243 0.271893\n8853 43.727733 -0.048174 -1.169783 1.200840 -0.027881 0.073049 0.958171 0.275309\n8854 43.736418 -0.050317 -1.172838 1.198384 -0.022959 0.070372 0.957481 0.278839\n8855 43.745885 -0.052448 -1.175056 1.195972 -0.025871 0.071430 0.956571 0.281425\n8856 43.753846 -0.054673 -1.177453 1.193324 -0.022562 0.069563 0.955721 0.285044\n8857 43.762936 -0.056633 -1.180658 1.191149 -0.020649 0.069736 0.955119 0.287156\n8858 43.769976 -0.058557 -1.182928 1.188434 -0.023856 0.072669 0.954175 0.289310\n8859 43.778259 -0.060300 -1.186167 1.185530 -0.015672 0.070360 0.954238 0.290232\n8860 43.785373 -0.062389 -1.188343 1.183344 -0.020073 0.072497 0.952998 0.293489\n8861 43.797225 -0.064091 -1.191965 1.180737 -0.017017 0.073435 0.952324 0.295630\n8862 43.802909 -0.065564 -1.194223 1.177960 -0.015427 0.072981 0.952197 0.296238\n8863 43.812285 -0.067292 -1.196726 1.175266 -0.013930 0.072661 0.952123 0.296628\n8864 43.819466 -0.068723 -1.198978 1.172539 -0.018481 0.075087 0.951361 0.298217\n8865 43.827512 -0.070557 -1.202051 1.169930 -0.013454 0.072265 0.951509 0.298709\n8866 43.836976 -0.072106 -1.204865 1.167264 -0.012900 0.072606 0.950966 0.300374\n8867 43.845855 -0.073723 -1.207581 1.164312 -0.015392 0.071679 0.950844 0.300868\n8868 43.853273 -0.074766 -1.210252 1.161448 -0.016048 0.071996 0.950374 0.302238\n8869 43.860445 -0.076502 -1.213793 1.158590 -0.008893 0.068858 0.950551 0.302709\n8870 43.869924 -0.077313 -1.215926 1.155956 -0.009375 0.068113 0.950006 0.304567\n8871 43.878631 -0.078848 -1.219010 1.153178 -0.012078 0.066831 0.949886 0.305131\n8872 43.886404 -0.079899 -1.222292 1.150279 -0.005918 0.066451 0.949475 0.306671\n8873 43.893752 -0.080922 -1.224823 1.147446 -0.008986 0.064647 0.949357 0.307346\n8874 43.903601 -0.081150 -1.227819 1.144562 -0.007304 0.062909 0.948969 0.308946\n8875 43.913489 -0.082647 -1.230827 1.141562 -0.001688 0.061896 0.948882 0.309497\n8876 43.919632 -0.083555 -1.233946 1.138557 -0.002874 0.061240 0.948457 0.310920\n8877 43.929076 -0.084604 -1.237122 1.135424 0.000354 0.059786 0.948126 0.312221\n8878 43.936459 -0.085539 -1.240063 1.132290 0.001247 0.059055 0.947792 0.313370\n8879 43.945316 -0.085966 -1.243152 1.129101 0.003385 0.056929 0.947549 0.314482\n8880 43.954512 -0.086770 -1.246278 1.125895 0.004546 0.055215 0.947296 0.315533\n8881 43.961532 -0.087667 -1.249306 1.122547 0.005136 0.054317 0.946979 0.316629\n8882 43.971667 -0.088296 -1.252425 1.119271 0.006466 0.052247 0.946769 0.317581\n8883 43.978704 -0.088940 -1.255726 1.116034 0.007533 0.049031 0.946553 0.318711\n8884 43.986732 -0.088898 -1.258814 1.112930 0.009233 0.047313 0.946019 0.320507\n8885 43.993659 -0.090196 -1.261851 1.109470 0.007802 0.045174 0.946410 0.319697\n8886 44.002736 -0.091105 -1.264799 1.106107 0.006106 0.044767 0.946266 0.320219\n8887 44.012189 -0.091554 -1.268072 1.102892 0.006685 0.041966 0.946310 0.320455\n8888 44.020360 -0.092224 -1.271103 1.099567 0.006092 0.040637 0.946237 0.320854\n8889 44.028209 -0.092686 -1.274208 1.096159 0.006725 0.038384 0.946544 0.320213\n8890 44.037467 -0.093307 -1.277730 1.092709 0.006161 0.037947 0.946613 0.320071\n8891 44.045746 -0.093958 -1.279976 1.089416 0.001539 0.038505 0.946653 0.319943\n8892 44.052601 -0.094174 -1.283099 1.085914 0.004026 0.034703 0.947335 0.318333\n8893 44.060437 -0.094264 -1.286541 1.082834 0.002071 0.035128 0.946516 0.320734\n8894 44.069476 -0.095124 -1.289126 1.079518 0.000772 0.033252 0.946971 0.319594\n8895 44.076985 -0.095429 -1.292030 1.076190 -0.000341 0.033737 0.946907 0.319732\n8896 44.086811 -0.095610 -1.295123 1.072934 0.000728 0.031230 0.947045 0.319579\n8897 44.094420 -0.095846 -1.298136 1.069660 0.000167 0.029665 0.947036 0.319755\n8898 44.102090 -0.096123 -1.301103 1.066457 0.000883 0.028965 0.947060 0.319747\n8899 44.113308 -0.096533 -1.303980 1.063209 -0.000692 0.029402 0.947003 0.319877\n8900 44.120093 -0.096672 -1.306875 1.060082 -0.000285 0.028688 0.946966 0.320049\n8901 44.127486 -0.096633 -1.309943 1.057105 0.002067 0.026279 0.946979 0.320213\n8902 44.137177 -0.096828 -1.312695 1.054080 0.002055 0.026093 0.946893 0.320483\n8903 44.145452 -0.096763 -1.315477 1.051146 0.003164 0.025659 0.946780 0.320842\n8904 44.153093 -0.096653 -1.318215 1.048265 0.004117 0.025515 0.946706 0.321060\n8905 44.162019 -0.096477 -1.321102 1.045639 0.007087 0.023643 0.946734 0.321069\n8906 44.168895 -0.096637 -1.323697 1.042808 0.006989 0.025185 0.946633 0.321253\n8907 44.178009 -0.096709 -1.326455 1.040157 0.009118 0.024522 0.946606 0.321330\n8908 44.186473 -0.096572 -1.329122 1.037577 0.010679 0.024010 0.946590 0.321366\n8909 44.193671 -0.096927 -1.331848 1.035089 0.012713 0.022524 0.946508 0.321643\n8910 44.202108 -0.096694 -1.334376 1.032490 0.012729 0.023255 0.946330 0.322113\n8911 44.212210 -0.097646 -1.337186 1.030144 0.014878 0.021879 0.946202 0.322494\n8912 44.219473 -0.096745 -1.339774 1.027762 0.016786 0.020615 0.945962 0.323185\n8913 44.228229 -0.096885 -1.342369 1.025387 0.017658 0.020016 0.945780 0.323711\n8914 44.236924 -0.096799 -1.344995 1.023005 0.017824 0.019932 0.945497 0.324532\n8915 44.243672 -0.097973 -1.347424 1.020706 0.017348 0.020002 0.945490 0.324573\n8916 44.252167 -0.097472 -1.349775 1.018501 0.016923 0.019874 0.945257 0.325280\n8917 44.260562 -0.097526 -1.352334 1.016320 0.017327 0.018559 0.945139 0.325680\n8918 44.270657 -0.096961 -1.354499 1.014001 0.015536 0.020290 0.944770 0.326738\n8919 44.278681 -0.097972 -1.356776 1.011796 0.013346 0.022028 0.944829 0.326551\n8920 44.286662 -0.098379 -1.359030 1.009658 0.011756 0.022614 0.944706 0.326927\n8921 44.294535 -0.098847 -1.361336 1.007638 0.011159 0.022764 0.944527 0.327454\n8922 44.302108 -0.098989 -1.363612 1.005669 0.011363 0.022209 0.944417 0.327804\n8923 44.313355 -0.099326 -1.365642 1.003449 0.009180 0.025360 0.944095 0.328569\n8924 44.319329 -0.100410 -1.368061 1.001515 0.009899 0.024810 0.943775 0.329509\n8925 44.328760 -0.099746 -1.369894 0.999464 0.009448 0.026439 0.943399 0.330468\n8926 44.337191 -0.100477 -1.372253 0.997547 0.010837 0.025461 0.943022 0.331578\n8927 44.344113 -0.099525 -1.374091 0.995617 0.011304 0.026129 0.942672 0.332505\n8928 44.353256 -0.099374 -1.376193 0.993660 0.012755 0.027223 0.942205 0.333687\n8929 44.362712 -0.099834 -1.378190 0.991845 0.013044 0.027923 0.942046 0.334065\n8930 44.370690 -0.099940 -1.380049 0.990073 0.015023 0.027749 0.941854 0.334538\n8931 44.379344 -0.099987 -1.381976 0.988213 0.016643 0.028231 0.941587 0.335171\n8932 44.386428 -0.099575 -1.383835 0.986304 0.017432 0.030281 0.941093 0.336338\n8933 44.395681 -0.100116 -1.385662 0.984526 0.019016 0.030922 0.940890 0.336762\n8934 44.403214 -0.099870 -1.387271 0.982814 0.020349 0.031040 0.940458 0.337878\n8935 44.411394 -0.100309 -1.389576 0.980972 0.022834 0.030373 0.939920 0.339275\n8936 44.419917 -0.099746 -1.390815 0.979543 0.022862 0.031506 0.939543 0.340210\n8937 44.428589 -0.099791 -1.392290 0.977967 0.023815 0.031804 0.939193 0.341083\n8938 44.436716 -0.099661 -1.393749 0.976442 0.024032 0.032969 0.938809 0.342014\n8939 44.444391 -0.099804 -1.395305 0.974916 0.024494 0.033477 0.938466 0.342872\n8940 44.452118 -0.099258 -1.396758 0.973512 0.025959 0.033445 0.938162 0.343597\n8941 44.464505 -0.099458 -1.398264 0.972140 0.026669 0.033462 0.938088 0.343743\n8942 44.469480 -0.099006 -1.399799 0.970759 0.027077 0.034813 0.937735 0.344539\n8943 44.477648 -0.098516 -1.401013 0.969412 0.026719 0.036078 0.937512 0.345044\n8944 44.486873 -0.099377 -1.402311 0.968198 0.027699 0.036104 0.937790 0.344209\n8945 44.496020 -0.099496 -1.403576 0.966876 0.026748 0.038065 0.937590 0.344617\n8946 44.502005 -0.099162 -1.405051 0.965568 0.027805 0.037000 0.937617 0.344576\n8947 44.511399 -0.099369 -1.406103 0.964317 0.025792 0.040373 0.937391 0.344968\n8948 44.519531 -0.098254 -1.407432 0.962901 0.026321 0.039943 0.937109 0.345744\n8949 44.527671 -0.099050 -1.408680 0.961614 0.026071 0.041082 0.937131 0.345568\n8950 44.537997 -0.098836 -1.410358 0.960276 0.027307 0.039987 0.936941 0.346116\n8951 44.544682 -0.098382 -1.411538 0.958970 0.028655 0.039495 0.936826 0.346376\n8952 44.551987 -0.098451 -1.412787 0.957700 0.028507 0.039021 0.936789 0.346541\n8953 44.560610 -0.097983 -1.414194 0.956422 0.030876 0.037395 0.936630 0.346946\n8954 44.569398 -0.097801 -1.415305 0.955147 0.031876 0.037247 0.936665 0.346778\n8955 44.578554 -0.098431 -1.416586 0.954004 0.032812 0.035653 0.936912 0.346191\n8956 44.587683 -0.098596 -1.417843 0.952826 0.034173 0.034359 0.937061 0.345787\n8957 44.596208 -0.097285 -1.419114 0.951663 0.034990 0.033265 0.936864 0.346346\n8958 44.604895 -0.098107 -1.420752 0.950779 0.036268 0.030980 0.937273 0.345318\n8959 44.611580 -0.097906 -1.421245 0.949674 0.035187 0.031737 0.937534 0.344653\n8960 44.618737 -0.098108 -1.422375 0.948838 0.035528 0.030027 0.937665 0.344414\n8961 44.628485 -0.098113 -1.423338 0.948075 0.035725 0.027401 0.937982 0.343749\n8962 44.636262 -0.098510 -1.424314 0.947267 0.035236 0.027689 0.938249 0.343045\n8963 44.645315 -0.097848 -1.425145 0.946559 0.034152 0.026997 0.938282 0.343122\n8964 44.654348 -0.098211 -1.426075 0.946063 0.033332 0.025365 0.938528 0.342652\n8965 44.660363 -0.097721 -1.427000 0.945394 0.032003 0.025209 0.938560 0.342702\n8966 44.668750 -0.098040 -1.428265 0.945086 0.032302 0.025625 0.939015 0.341395\n8967 44.680195 -0.097827 -1.428266 0.944191 0.029396 0.027049 0.939084 0.341359\n8968 44.686450 -0.097420 -1.428864 0.943565 0.028209 0.028084 0.939224 0.340989\n8969 44.694471 -0.097477 -1.429749 0.942973 0.026967 0.029037 0.939446 0.340398\n8970 44.703732 -0.097803 -1.430380 0.942325 0.026337 0.031129 0.939767 0.339374\n8971 44.711891 -0.097796 -1.431108 0.941624 0.026082 0.033128 0.939931 0.338750\n8972 44.718992 -0.097202 -1.431878 0.940773 0.025980 0.034597 0.939919 0.338646\n8973 44.727759 -0.097372 -1.432179 0.939937 0.024796 0.037945 0.940112 0.337839\n8974 44.737621 -0.096792 -1.432960 0.939102 0.026174 0.038325 0.940247 0.337315\n8975 44.744671 -0.096580 -1.433660 0.938246 0.025931 0.039062 0.940439 0.336714\n8976 44.753339 -0.096444 -1.434566 0.937422 0.027584 0.038300 0.940678 0.336000\n8977 44.760575 -0.095939 -1.435342 0.936528 0.027327 0.038368 0.940752 0.335809\n8978 44.769316 -0.095370 -1.436571 0.935696 0.029978 0.034905 0.940964 0.335365\n8979 44.779127 -0.095674 -1.437430 0.934752 0.031124 0.033605 0.941442 0.334050\n8980 44.786369 -0.094474 -1.438080 0.933699 0.032781 0.031428 0.941712 0.333340\n8981 44.793892 -0.094754 -1.439063 0.932781 0.034053 0.028406 0.942270 0.331905\n8982 44.802147 -0.093914 -1.440188 0.931816 0.034435 0.025920 0.942624 0.331063\n8983 44.811884 -0.094004 -1.440991 0.930711 0.034950 0.024554 0.943289 0.329215\n8984 44.820358 -0.093296 -1.442219 0.929710 0.036677 0.021255 0.943731 0.327986\n8985 44.828730 -0.093358 -1.443028 0.928697 0.036756 0.019806 0.944520 0.325788\n8986 44.836377 -0.093016 -1.443885 0.927624 0.036667 0.018520 0.945205 0.323883\n8987 44.843693 -0.092164 -1.444660 0.926568 0.035965 0.016963 0.945759 0.322427\n8988 44.852176 -0.091734 -1.445574 0.925695 0.036921 0.013127 0.946566 0.320121\n8989 44.863034 -0.090936 -1.446550 0.924584 0.038292 0.009444 0.947229 0.318122\n8990 44.869657 -0.091080 -1.447223 0.923628 0.036267 0.009618 0.948256 0.315282\n8991 44.878841 -0.090178 -1.447945 0.922608 0.037438 0.005014 0.949037 0.312894\n8992 44.886919 -0.090043 -1.448585 0.921557 0.034053 0.006339 0.949795 0.310948\n8993 44.893653 -0.089880 -1.449363 0.920558 0.034632 0.003165 0.950778 0.307916\n8994 44.903227 -0.089380 -1.450272 0.919653 0.035046 0.000409 0.951554 0.305478\n8995 44.911624 -0.089007 -1.450931 0.918521 0.033498 -0.000297 0.952307 0.303299\n8996 44.919955 -0.088305 -1.451360 0.917531 0.033207 -0.002294 0.953238 0.300382\n8997 44.929232 -0.087784 -1.452262 0.916468 0.034142 -0.005033 0.953985 0.297861\n8998 44.937556 -0.087328 -1.453169 0.915290 0.034391 -0.007257 0.954407 0.296431\n8999 44.945645 -0.086798 -1.453503 0.914307 0.034427 -0.007147 0.955570 0.292662\n9000 44.953296 -0.086330 -1.454340 0.913294 0.035525 -0.008916 0.955856 0.291543\n9001 44.961491 -0.085693 -1.454962 0.911836 0.036947 -0.010012 0.956991 0.287582\n9002 44.969739 -0.085008 -1.455315 0.910657 0.037865 -0.011275 0.957639 0.285248\n9003 44.978672 -0.084434 -1.456243 0.909363 0.041406 -0.015342 0.958093 0.283033\n9004 44.986372 -0.084369 -1.456699 0.908289 0.040554 -0.015646 0.958821 0.280666\n9005 44.993810 -0.083375 -1.457306 0.907138 0.042394 -0.018411 0.959088 0.279309\n9006 45.002238 -0.083086 -1.458103 0.905977 0.043932 -0.020277 0.959645 0.277021\n9007 45.012845 -0.082778 -1.458533 0.904956 0.045298 -0.022114 0.960038 0.275293\n9008 45.019671 -0.082320 -1.459177 0.904030 0.047736 -0.026570 0.960104 0.274256\n9009 45.028731 -0.082413 -1.459741 0.903478 0.047864 -0.027699 0.960693 0.272049\n9010 45.037151 -0.082404 -1.459977 0.903196 0.047722 -0.029435 0.961139 0.270311\n9011 45.043654 -0.082397 -1.460179 0.903060 0.047611 -0.031098 0.961345 0.269412\n9012 45.055016 -0.082224 -1.460473 0.902803 0.046115 -0.031070 0.961389 0.269516\n9013 45.060907 -0.081967 -1.460643 0.902650 0.047264 -0.032224 0.961596 0.268443\n9014 45.068707 -0.082221 -1.460716 0.902439 0.047857 -0.033181 0.961668 0.267962\n9015 45.076974 -0.082097 -1.460519 0.902362 0.046891 -0.032640 0.961616 0.268385\n9016 45.086261 -0.082353 -1.460490 0.902709 0.045173 -0.030510 0.962113 0.267147\n9017 45.094058 -0.082857 -1.460339 0.902936 0.042487 -0.028052 0.962378 0.266903\n9018 45.103503 -0.082650 -1.460206 0.903120 0.042861 -0.027771 0.962344 0.266994\n9019 45.112707 -0.083030 -1.459961 0.903336 0.038463 -0.024676 0.962520 0.267335\n9020 45.120651 -0.083839 -1.460598 0.903554 0.040116 -0.026385 0.962857 0.265708\n9021 45.127700 -0.083791 -1.460426 0.903619 0.040055 -0.026322 0.962983 0.265268\n9022 45.135693 -0.082858 -1.460220 0.903606 0.041666 -0.027840 0.962681 0.265958\n9023 45.144768 -0.082934 -1.460379 0.903323 0.042559 -0.028811 0.962962 0.264694\n9024 45.152541 -0.082822 -1.460767 0.902958 0.044085 -0.031077 0.963006 0.264028\n9025 45.160453 -0.082133 -1.460208 0.902494 0.046721 -0.033957 0.963067 0.262994\n9026 45.168662 -0.082896 -1.460885 0.901955 0.048059 -0.036902 0.963260 0.261647\n9027 45.179551 -0.081886 -1.461617 0.901345 0.051181 -0.042600 0.962813 0.261836\n9028 45.186693 -0.082422 -1.461726 0.900517 0.051168 -0.044991 0.963117 0.260313\n9029 45.195416 -0.081540 -1.462968 0.899724 0.055064 -0.051662 0.962200 0.261668\n9030 45.203594 -0.081743 -1.463032 0.898793 0.055648 -0.055004 0.962428 0.260021\n9031 45.210910 -0.082319 -1.464019 0.897522 0.058660 -0.059747 0.962591 0.257698\n9032 45.219830 -0.082426 -1.464293 0.896844 0.057603 -0.062850 0.962449 0.257728\n9033 45.228367 -0.082203 -1.464810 0.895944 0.057707 -0.067182 0.962194 0.257564\n9034 45.235239 -0.082362 -1.465282 0.895102 0.057572 -0.070586 0.962096 0.257050\n9035 45.244260 -0.082045 -1.465480 0.894285 0.055137 -0.073320 0.962077 0.256890\n9036 45.253444 -0.082511 -1.466073 0.893588 0.053440 -0.077159 0.962144 0.255871\n9037 45.261928 -0.082648 -1.466177 0.892665 0.049606 -0.079276 0.962028 0.256430\n9038 45.270000 -0.082587 -1.466857 0.891920 0.049140 -0.083688 0.961972 0.255325\n9039 45.277043 -0.082738 -1.467332 0.891098 0.046209 -0.084955 0.962366 0.253966\n9040 45.286037 -0.082647 -1.467529 0.890355 0.044335 -0.087447 0.962325 0.253612\n9041 45.295163 -0.082729 -1.468132 0.889839 0.042993 -0.090231 0.962480 0.252275\n9042 45.303333 -0.082571 -1.468958 0.889418 0.042363 -0.092143 0.962464 0.251750\n9043 45.310540 -0.082501 -1.468969 0.889009 0.043627 -0.093088 0.962906 0.249487\n9044 45.318677 -0.082046 -1.469159 0.888706 0.043379 -0.092334 0.963241 0.248513\n9045 45.329669 -0.081451 -1.469290 0.888310 0.043209 -0.091240 0.963203 0.249096\n9046 45.336704 -0.081237 -1.469936 0.888167 0.046665 -0.092725 0.963664 0.246121\n9047 45.345259 -0.081214 -1.470048 0.887919 0.047039 -0.092119 0.963847 0.245563\n9048 45.353641 -0.080253 -1.469559 0.888093 0.046036 -0.091587 0.964118 0.244884\n9049 45.360296 -0.079630 -1.470739 0.887673 0.047509 -0.093364 0.964040 0.244240\n9050 45.370724 -0.080333 -1.470743 0.887633 0.044214 -0.088336 0.965185 0.242199\n9051 45.378291 -0.080241 -1.471074 0.887531 0.042632 -0.087303 0.965696 0.240814\n9052 45.386501 -0.080358 -1.472076 0.887319 0.041151 -0.086566 0.966023 0.240025\n9053 45.394612 -0.079560 -1.471467 0.887361 0.039049 -0.084908 0.966475 0.239150\n9054 45.402231 -0.080045 -1.471383 0.887045 0.036781 -0.081812 0.967584 0.236083\n9055 45.414865 -0.079400 -1.472216 0.886978 0.037017 -0.082368 0.967559 0.235954\n9056 45.419727 -0.079040 -1.472130 0.886503 0.033013 -0.079824 0.968247 0.234598\n9057 45.427552 -0.078957 -1.472608 0.886154 0.034929 -0.079087 0.968745 0.232506\n9058 45.436543 -0.078454 -1.471798 0.885690 0.031293 -0.076141 0.969346 0.231497\n9059 45.444683 -0.078291 -1.472338 0.885134 0.031069 -0.073714 0.969977 0.229663\n9060 45.451841 -0.078227 -1.472705 0.884396 0.029501 -0.070027 0.970714 0.227902\n9061 45.462148 -0.078296 -1.472760 0.883873 0.027497 -0.067183 0.971377 0.226178\n9062 45.469061 -0.078087 -1.472553 0.883209 0.024735 -0.063211 0.971794 0.225853\n9063 45.479189 -0.078064 -1.472338 0.882766 0.025606 -0.060968 0.972277 0.224287\n9064 45.486708 -0.078225 -1.472897 0.882246 0.025873 -0.059543 0.972651 0.223016\n9065 45.495492 -0.078166 -1.472168 0.881844 0.024245 -0.055671 0.973196 0.221817\n9066 45.503419 -0.078273 -1.471956 0.881512 0.022981 -0.053720 0.973384 0.221609\n9067 45.510363 -0.078346 -1.471541 0.881106 0.021663 -0.051377 0.973377 0.222326\n9068 45.519202 -0.078420 -1.471270 0.881010 0.022291 -0.051575 0.973536 0.221518\n9069 45.527582 -0.078742 -1.471146 0.880662 0.020408 -0.049219 0.973632 0.221816\n9070 45.537490 -0.078903 -1.470671 0.880805 0.021130 -0.050242 0.973598 0.221665\n9071 45.544961 -0.078984 -1.470526 0.880726 0.021561 -0.051302 0.973464 0.221972\n9072 45.553089 -0.079286 -1.469637 0.880522 0.018618 -0.048152 0.973862 0.221197\n9073 45.561044 -0.079196 -1.468902 0.880525 0.019819 -0.048554 0.973824 0.221172\n9074 45.568920 -0.079440 -1.468817 0.880358 0.018834 -0.046920 0.974130 0.220259\n9075 45.580715 -0.079353 -1.467899 0.880323 0.018908 -0.045795 0.974218 0.220102\n9076 45.586052 -0.079134 -1.467964 0.880330 0.021513 -0.046513 0.974129 0.220107\n9077 45.594230 -0.079233 -1.467225 0.880207 0.022213 -0.044559 0.974775 0.217566\n9078 45.603533 -0.078954 -1.466592 0.879962 0.022718 -0.042213 0.974967 0.217119\n9079 45.612080 -0.078792 -1.466097 0.879770 0.023477 -0.040930 0.975172 0.216363\n9080 45.618939 -0.078616 -1.465583 0.879540 0.023894 -0.039771 0.975283 0.216032\n9081 45.626909 -0.078845 -1.465126 0.879049 0.023521 -0.037772 0.975451 0.215675\n9082 45.637214 -0.078456 -1.464532 0.878891 0.023758 -0.036670 0.975551 0.215388\n9083 45.645001 -0.078664 -1.464307 0.878333 0.024726 -0.035468 0.975903 0.213878\n9084 45.654128 -0.078179 -1.463278 0.878157 0.023706 -0.034693 0.975794 0.214615\n9085 45.662305 -0.078161 -1.462721 0.878001 0.022903 -0.034327 0.975777 0.214841\n9086 45.669748 -0.078095 -1.461497 0.877991 0.021594 -0.034602 0.975861 0.214549\n9087 45.679427 -0.078309 -1.461601 0.877884 0.022545 -0.035359 0.976047 0.213482\n9088 45.686672 -0.078220 -1.461623 0.877802 0.021139 -0.034506 0.976083 0.213599\n9089 45.695959 -0.078053 -1.460945 0.877676 0.019512 -0.033552 0.975975 0.214399\n9090 45.703138 -0.077845 -1.460414 0.877591 0.020102 -0.033812 0.975841 0.214911\n9091 45.712031 -0.077926 -1.459570 0.877317 0.017322 -0.030873 0.975896 0.215344\n9092 45.719235 -0.077849 -1.459336 0.877069 0.019463 -0.029619 0.975851 0.215542\n9093 45.727607 -0.077749 -1.459090 0.876550 0.019916 -0.026968 0.975958 0.215366\n9094 45.737462 -0.077974 -1.458431 0.876463 0.019636 -0.025046 0.976070 0.215114\n9095 45.745502 -0.078055 -1.457557 0.876149 0.018846 -0.025188 0.976000 0.215487\n9096 45.753610 -0.078363 -1.456601 0.875969 0.017066 -0.024217 0.976022 0.215649\n9097 45.760744 -0.078543 -1.455974 0.875695 0.016396 -0.023848 0.975922 0.216194\n9098 45.768725 -0.078471 -1.455238 0.875421 0.016293 -0.024094 0.976121 0.215271\n9099 45.778657 -0.078792 -1.455070 0.875286 0.016889 -0.026201 0.975921 0.215885\n9100 45.786332 -0.078962 -1.454358 0.875145 0.015591 -0.026161 0.976035 0.215473\n9101 45.793630 -0.079083 -1.453817 0.874977 0.014242 -0.025815 0.976067 0.215465\n9102 45.802197 -0.078998 -1.453950 0.874818 0.014777 -0.027150 0.975881 0.216102\n9103 45.813087 -0.079337 -1.453505 0.874579 0.012610 -0.026463 0.976042 0.215598\n9104 45.819088 -0.079438 -1.453724 0.874352 0.011404 -0.027418 0.976030 0.215599\n9105 45.828244 -0.079905 -1.453481 0.874101 0.007990 -0.026192 0.976230 0.214999\n9106 45.837464 -0.079967 -1.453480 0.873967 0.008424 -0.027775 0.976384 0.214085\n9107 45.845331 -0.080673 -1.452943 0.873825 0.008135 -0.027510 0.976573 0.213266\n9108 45.853224 -0.080412 -1.452515 0.873665 0.006161 -0.025654 0.976894 0.212090\n9109 45.860400 -0.080546 -1.452484 0.873561 0.005616 -0.024294 0.977115 0.211247\n9110 45.869172 -0.080606 -1.452156 0.873450 0.005616 -0.022928 0.977345 0.210331\n9111 45.879212 -0.080495 -1.452036 0.873339 0.007981 -0.022618 0.977540 0.209383\n9112 45.886854 -0.080718 -1.451466 0.873170 0.006045 -0.019038 0.977726 0.208935\n9113 45.896754 -0.080839 -1.451216 0.873011 0.005241 -0.017154 0.977827 0.208644\n9114 45.902474 -0.081095 -1.450649 0.872801 0.002303 -0.014512 0.978040 0.207900\n9115 45.910888 -0.081191 -1.450091 0.872606 0.001635 -0.013189 0.978177 0.207347\n9116 45.920360 -0.081476 -1.449728 0.872476 0.002897 -0.012990 0.978271 0.206903\n9117 45.929227 -0.081474 -1.449109 0.872053 0.000302 -0.010010 0.978403 0.206464\n9118 45.938223 -0.081599 -1.449614 0.871766 0.001193 -0.010374 0.978303 0.206914\n9119 45.945914 -0.081869 -1.447993 0.871440 -0.002164 -0.007478 0.978680 0.205243\n9120 45.954939 -0.081959 -1.447486 0.871205 -0.001947 -0.007147 0.978806 0.204654\n9121 45.961840 -0.081850 -1.446992 0.870998 -0.001468 -0.007354 0.978903 0.204189\n9122 45.969816 -0.081571 -1.446549 0.870748 0.000154 -0.008045 0.978953 0.203928\n9123 45.977633 -0.081458 -1.446062 0.870441 0.001131 -0.008228 0.978991 0.203734\n9124 45.985726 -0.081413 -1.445378 0.870143 0.002142 -0.007798 0.979147 0.202991\n9125 45.995273 -0.081330 -1.444979 0.869843 0.003226 -0.007327 0.979188 0.202796\n9126 46.003496 -0.081337 -1.444365 0.869613 0.003401 -0.006689 0.979317 0.202194\n9127 46.010251 -0.081380 -1.443690 0.869393 0.003072 -0.005300 0.979435 0.201668\n9128 46.018444 -0.081443 -1.442990 0.869194 0.002340 -0.004951 0.979513 0.201305\n9129 46.029577 -0.081497 -1.442591 0.869116 0.002780 -0.004467 0.979631 0.200737\n9130 46.036549 -0.081560 -1.442082 0.868935 0.001746 -0.003447 0.979726 0.200306\n9131 46.045212 -0.081570 -1.442294 0.868781 0.001804 -0.003242 0.979599 0.200930\n9132 46.053496 -0.081783 -1.441001 0.868646 -0.001961 0.000123 0.979860 0.199674\n9133 46.060132 -0.081845 -1.440495 0.868399 -0.003923 0.002516 0.979883 0.199516\n9134 46.070031 -0.081871 -1.439985 0.868045 -0.006619 0.004773 0.979909 0.199277\n9135 46.078411 -0.081841 -1.439609 0.867664 -0.008300 0.008021 0.979871 0.199296\n9136 46.087848 -0.081793 -1.439287 0.867089 -0.008852 0.010075 0.979870 0.199185\n9137 46.094223 -0.081397 -1.438716 0.866553 -0.006851 0.014309 0.979952 0.198601\n9138 46.101828 -0.081266 -1.438847 0.865947 -0.004380 0.016250 0.979947 0.198544\n9139 46.110221 -0.081046 -1.438950 0.865831 -0.001884 0.018495 0.979995 0.198151\n9140 46.119340 -0.080990 -1.438348 0.865993 -0.001429 0.021147 0.980052 0.197606\n9141 46.128364 -0.080839 -1.438422 0.865925 -0.001247 0.021449 0.980039 0.197640\n9142 46.137217 -0.080480 -1.438227 0.865752 0.001166 0.021422 0.980139 0.197150\n9143 46.144017 -0.080253 -1.438627 0.865506 0.003072 0.019756 0.980128 0.197358\n9144 46.152103 -0.080433 -1.438636 0.865336 0.001843 0.018188 0.980033 0.197992\n9145 46.162784 -0.080910 -1.438519 0.865434 -0.002286 0.019095 0.979926 0.198435\n9146 46.170065 -0.081125 -1.438783 0.865161 -0.002599 0.017010 0.979732 0.199570\n9147 46.178299 -0.081059 -1.439056 0.865337 -0.001976 0.017544 0.979977 0.198325\n9148 46.187709 -0.080745 -1.438635 0.865449 -0.000714 0.016856 0.979910 0.198725\n9149 46.194628 -0.080737 -1.438613 0.865564 -0.001425 0.018550 0.979922 0.198511\n9150 46.203421 -0.080792 -1.438384 0.865833 -0.002412 0.018677 0.979890 0.198650\n9151 46.211586 -0.080742 -1.439168 0.865987 -0.001915 0.018113 0.979639 0.199939\n9152 46.219772 -0.080654 -1.438277 0.866009 -0.001720 0.019130 0.979873 0.198696\n9153 46.228690 -0.080671 -1.438356 0.865992 -0.001034 0.019003 0.979876 0.198699\n9154 46.236487 -0.080745 -1.438235 0.866002 -0.002548 0.019067 0.979794 0.199082\n9155 46.245016 -0.080831 -1.438780 0.866070 -0.003701 0.018358 0.979628 0.199945\n9156 46.252548 -0.081034 -1.438164 0.866012 -0.005347 0.019970 0.979825 0.198786\n9157 46.262255 -0.080986 -1.438130 0.866019 -0.003287 0.019822 0.979951 0.198225\n9158 46.269495 -0.080626 -1.438871 0.865796 -0.001477 0.018416 0.979806 0.199096\n9159 46.277171 -0.080867 -1.438423 0.866061 -0.002644 0.019371 0.979805 0.198997\n9160 46.285267 -0.081024 -1.438147 0.865920 -0.005187 0.020406 0.979791 0.198914\n9161 46.296228 -0.080864 -1.438334 0.865991 -0.002618 0.018663 0.979841 0.198888\n9162 46.302711 -0.080707 -1.438398 0.865880 -0.001615 0.018475 0.979866 0.198795\n9163 46.312399 -0.080727 -1.438569 0.865729 -0.001771 0.018884 0.979920 0.198489\n9164 46.319521 -0.080751 -1.438428 0.865851 -0.001953 0.017912 0.979851 0.198918\n9165 46.327263 -0.080463 -1.438428 0.865933 -0.002156 0.016789 0.979568 0.200398\n9166 46.337164 -0.080795 -1.438429 0.865800 -0.002454 0.018928 0.979927 0.198440\n9167 46.344772 -0.080832 -1.438341 0.865732 -0.002465 0.019727 0.979916 0.198416\n9168 46.352229 -0.080480 -1.439058 0.865801 -0.000816 0.018109 0.979713 0.199587\n9169 46.361454 -0.080740 -1.438670 0.865841 -0.002375 0.018976 0.979788 0.199121\n9170 46.368977 -0.080740 -1.438392 0.865953 -0.002323 0.018544 0.979802 0.199093\n9171 46.377080 -0.081083 -1.438653 0.865794 -0.002590 0.020153 0.980017 0.197874\n9172 46.386469 -0.080809 -1.438683 0.865554 -0.001283 0.018192 0.979612 0.200069\n9173 46.394320 -0.080580 -1.438453 0.866173 -0.002127 0.018803 0.979685 0.199649\n9174 46.403116 -0.080700 -1.438372 0.866026 -0.002286 0.018664 0.979893 0.198638\n9175 46.410179 -0.080706 -1.438547 0.866041 -0.002668 0.019062 0.979809 0.199009\n9176 46.419550 -0.080910 -1.438506 0.865970 -0.003514 0.020272 0.979855 0.198646\n9177 46.428449 -0.080769 -1.438655 0.865668 -0.000943 0.018974 0.979990 0.198137\n9178 46.436849 -0.080334 -1.438555 0.865957 -0.001164 0.017234 0.979666 0.199891\n9179 46.443640 -0.080408 -1.438253 0.866075 -0.001812 0.018449 0.979715 0.199539\n9180 46.451796 -0.080936 -1.438344 0.865936 -0.004102 0.020243 0.979831 0.198758\n9181 46.463318 -0.080752 -1.438590 0.865953 -0.002857 0.019589 0.979858 0.198713\n9182 46.469309 -0.080595 -1.438759 0.865642 -0.000740 0.018229 0.979843 0.198934\n9183 46.478357 -0.080637 -1.438398 0.865970 -0.002040 0.018523 0.979879 0.198721\n9184 46.486382 -0.080838 -1.438261 0.865928 -0.003587 0.019693 0.979841 0.198773\n9185 46.493486 -0.080739 -1.438368 0.865976 -0.002282 0.018880 0.979856 0.198798\n9186 46.503104 -0.080674 -1.438825 0.865944 -0.002372 0.019340 0.979728 0.199385\n9187 46.511347 -0.080806 -1.438301 0.865966 -0.002862 0.019803 0.979842 0.198771\n9188 46.519748 -0.080906 -1.438416 0.865932 -0.003464 0.020215 0.979840 0.198727\n9189 46.529260 -0.080539 -1.438258 0.866002 -0.001564 0.018390 0.979866 0.198803\n9190 46.536772 -0.080919 -1.438423 0.865948 -0.003638 0.020255 0.979855 0.198645\n9191 46.546606 -0.080647 -1.438659 0.865983 -0.002646 0.019374 0.979773 0.199154\n9192 46.552603 -0.080550 -1.438403 0.866005 -0.001734 0.018512 0.979848 0.198879\n9193 46.561966 -0.080641 -1.438368 0.866012 -0.002019 0.018892 0.979857 0.198797\n9194 46.569114 -0.080637 -1.438720 0.865984 -0.002586 0.019310 0.979704 0.199503\n9195 46.578093 -0.080754 -1.439273 0.865366 -0.000608 0.018450 0.979817 0.199044\n9196 46.586312 -0.080739 -1.438339 0.865988 -0.002370 0.019386 0.979856 0.198748\n9197 46.593595 -0.080722 -1.438344 0.865954 -0.002500 0.019332 0.979846 0.198802\n9198 46.602137 -0.080616 -1.438440 0.866103 -0.001566 0.018492 0.979713 0.199544\n9199 46.613046 -0.080891 -1.438511 0.865882 -0.003386 0.020082 0.979844 0.198723\n9200 46.619333 -0.080647 -1.438424 0.865944 -0.001836 0.018790 0.979859 0.198796\n9201 46.628275 -0.080628 -1.438559 0.866016 -0.001443 0.018486 0.979732 0.199453\n9202 46.636226 -0.080557 -1.438491 0.866050 -0.001909 0.018917 0.979673 0.199697\n9203 46.643617 -0.080711 -1.438365 0.865943 -0.002314 0.019308 0.979862 0.198728\n9204 46.653140 -0.080546 -1.438447 0.865938 -0.001462 0.018625 0.979844 0.198891\n9205 46.660792 -0.080314 -1.438994 0.865898 -0.000539 0.018017 0.979761 0.199356\n9206 46.668617 -0.080647 -1.438370 0.865967 -0.001949 0.019151 0.979852 0.198793\n9207 46.676991 -0.080686 -1.438398 0.865975 -0.002360 0.019439 0.979825 0.198898\n9208 46.687031 -0.080932 -1.438412 0.865911 -0.003583 0.020457 0.979853 0.198637\n9209 46.694576 -0.080539 -1.438411 0.865974 -0.001466 0.018589 0.979842 0.198904\n9210 46.703166 -0.080816 -1.438513 0.865938 -0.003203 0.020224 0.979839 0.198738\n9211 46.710168 -0.080655 -1.438452 0.866103 -0.001636 0.018837 0.979721 0.199474\n9212 46.719723 -0.080620 -1.438303 0.865675 -0.000499 0.017936 0.979962 0.198374\n9213 46.726858 -0.080320 -1.438781 0.865676 -0.000415 0.017734 0.979771 0.199333\n9214 46.736142 -0.080630 -1.438484 0.866045 -0.002017 0.019370 0.979674 0.199647\n9215 46.745334 -0.080852 -1.438558 0.865894 -0.003045 0.020206 0.979841 0.198732\n9216 46.751793 -0.080779 -1.438316 0.865931 -0.002701 0.019807 0.979850 0.198733\n9217 46.761294 -0.080521 -1.438332 0.865920 -0.001340 0.018640 0.979862 0.198799\n9218 46.769740 -0.080573 -1.438516 0.865825 -0.000941 0.018727 0.979838 0.198913\n9219 46.776946 -0.080692 -1.438414 0.865882 -0.002626 0.019984 0.979859 0.198673\n9220 46.785252 -0.080699 -1.438370 0.865920 -0.002187 0.019365 0.979858 0.198742\n9221 46.794918 -0.080772 -1.438818 0.865996 -0.001986 0.019140 0.979688 0.199601\n9222 46.803486 -0.080491 -1.438689 0.865925 -0.001263 0.018493 0.979753 0.199349\n9223 46.810337 -0.080770 -1.438324 0.865916 -0.002683 0.019809 0.979848 0.198743\n9224 46.820265 -0.081105 -1.438008 0.865471 -0.002471 0.019415 0.979590 0.200049\n9225 46.827169 -0.080423 -1.438797 0.865881 -0.001294 0.018012 0.979614 0.200077\n9226 46.836788 -0.080578 -1.437992 0.865693 -0.000994 0.019536 0.980060 0.197735\n9227 46.844775 -0.080699 -1.438646 0.865903 -0.002594 0.019877 0.979792 0.199014\n9228 46.853240 -0.080782 -1.438266 0.865907 -0.003190 0.020373 0.979837 0.198731\n9229 46.861024 -0.080808 -1.438292 0.865943 -0.002877 0.020065 0.979849 0.198707\n9230 46.869460 -0.080976 -1.438444 0.865868 -0.003544 0.020767 0.979864 0.198553\n9231 46.877963 -0.080724 -1.438366 0.865943 -0.002503 0.019791 0.979841 0.198780\n9232 46.886749 -0.080801 -1.438522 0.865893 -0.002972 0.020241 0.979827 0.198796\n9233 46.893699 -0.080749 -1.438291 0.865889 -0.003044 0.020304 0.979838 0.198735\n9234 46.903172 -0.080642 -1.438803 0.865893 -0.002292 0.019607 0.979739 0.199303\n9235 46.910846 -0.080901 -1.438517 0.865854 -0.003269 0.020520 0.979850 0.198650\n9236 46.918992 -0.080728 -1.438401 0.865909 -0.002405 0.019695 0.979842 0.198788\n9237 46.927094 -0.080270 -1.438360 0.865831 -0.001010 0.018177 0.979716 0.199562\n9238 46.936484 -0.080648 -1.437912 0.866128 -0.002618 0.018807 0.979470 0.200693\n9239 46.943986 -0.080648 -1.438408 0.865896 -0.001762 0.019195 0.979850 0.198804\n9240 46.954943 -0.081091 -1.438798 0.865723 -0.002362 0.020973 0.980028 0.197736\n9241 46.962659 -0.080601 -1.438487 0.865901 -0.000208 0.018757 0.979895 0.198629\n9242 46.970636 -0.080574 -1.438483 0.865880 -0.001492 0.018923 0.979828 0.198940\n9243 46.977547 -0.080428 -1.438927 0.865841 -0.001060 0.018232 0.979637 0.199943\n9244 46.985449 -0.080687 -1.438997 0.865875 -0.002124 0.019642 0.979701 0.199488\n9245 46.994374 -0.080826 -1.438680 0.865857 -0.002658 0.020264 0.979847 0.198701\n9246 47.003689 -0.080937 -1.438499 0.865830 -0.003349 0.020749 0.979857 0.198594\n9247 47.010465 -0.080560 -1.438201 0.866006 -0.001811 0.018992 0.979627 0.199920\n9248 47.020502 -0.080466 -1.438136 0.865902 -0.001272 0.018994 0.979852 0.198813\n9249 47.028570 -0.080851 -1.438551 0.865845 -0.003050 0.020511 0.979837 0.198718\n9250 47.036868 -0.081221 -1.438906 0.865752 -0.002657 0.021131 0.979997 0.197871\n9251 47.046668 -0.080782 -1.438323 0.865891 -0.002600 0.020057 0.979844 0.198739\n9252 47.056783 -0.080615 -1.438413 0.865848 0.000138 0.019091 0.979923 0.198462\n9253 47.061841 -0.080543 -1.438530 0.866034 -0.001629 0.019230 0.979630 0.199884\n9254 47.069881 -0.081145 -1.438848 0.865718 -0.002551 0.021188 0.980011 0.197795\n9255 47.078238 -0.080675 -1.438390 0.865880 -0.001901 0.019490 0.979849 0.198776\n9256 47.086780 -0.080761 -1.438346 0.865872 -0.002397 0.019912 0.979849 0.198729\n9257 47.094015 -0.081097 -1.438857 0.865697 -0.002160 0.020990 0.980021 0.197774\n9258 47.104227 -0.081086 -1.438860 0.865696 -0.002211 0.021030 0.980016 0.197791\n9259 47.111865 -0.080851 -1.438555 0.865823 -0.002895 0.020392 0.979828 0.198779\n9260 47.118850 -0.080495 -1.438579 0.865871 -0.001745 0.019294 0.979768 0.199197\n9261 47.130880 -0.080498 -1.438517 0.865766 -0.000778 0.018789 0.979793 0.199128\n9262 47.136351 -0.080561 -1.438426 0.865861 -0.001326 0.019074 0.979842 0.198859\n9263 47.145114 -0.081165 -1.438899 0.865709 -0.002422 0.021110 0.979999 0.197867\n9264 47.152787 -0.080466 -1.438672 0.865865 -0.001580 0.019275 0.979726 0.199406\n9265 47.160654 -0.080689 -1.438520 0.865871 -0.001921 0.019541 0.979817 0.198930\n9266 47.170002 -0.080613 -1.438281 0.865862 -0.002179 0.019859 0.979824 0.198861\n9267 47.178090 -0.080915 -1.438538 0.865796 -0.003156 0.020756 0.979850 0.198627\n9268 47.186811 -0.081202 -1.438915 0.865720 -0.002548 0.021175 0.979988 0.197910\n9269 47.195662 -0.080747 -1.438771 0.865812 -0.002390 0.020259 0.979814 0.198870\n9270 47.203415 -0.080541 -1.438600 0.865988 -0.001623 0.019290 0.979613 0.199961\n9271 47.211409 -0.080724 -1.438504 0.865466 -0.000986 0.019160 0.979749 0.199307\n9272 47.219666 -0.080964 -1.438493 0.865785 -0.003348 0.020889 0.979857 0.198576\n9273 47.227016 -0.080677 -1.438747 0.865815 -0.002276 0.019978 0.979766 0.199132\n9274 47.236234 -0.080777 -1.438845 0.865747 -0.000859 0.019393 0.979869 0.198697\n9275 47.245269 -0.080766 -1.438357 0.865847 -0.002520 0.020148 0.979841 0.198745\n9276 47.252018 -0.080371 -1.438638 0.865791 -0.000853 0.018389 0.979742 0.199416\n9277 47.260323 -0.080872 -1.438601 0.865791 -0.002930 0.020688 0.979850 0.198637\n9278 47.269653 -0.081170 -1.438888 0.865686 -0.002510 0.021296 0.980009 0.197792\n9279 47.276965 -0.080632 -1.438468 0.865849 -0.001644 0.019439 0.979829 0.198882\n9280 47.285366 -0.080671 -1.438596 0.865864 -0.001136 0.019350 0.979749 0.199287\n9281 47.296827 -0.080274 -1.439214 0.865720 -0.000139 0.018350 0.979764 0.199314\n9282 47.302581 -0.080917 -1.438455 0.865772 -0.003382 0.020943 0.979810 0.198804\n9283 47.311664 -0.080504 -1.438560 0.865906 -0.001555 0.018462 0.979543 0.200378\n9284 47.319268 -0.080730 -1.438333 0.865802 -0.002846 0.020562 0.979827 0.198768\n9285 47.327079 -0.080476 -1.438728 0.865850 -0.001520 0.019318 0.979706 0.199500\n9286 47.337357 -0.080452 -1.438167 0.865827 -0.001161 0.019036 0.979848 0.198832\n9287 47.344110 -0.080844 -1.438537 0.865416 -0.001356 0.019291 0.979645 0.199802\n9288 47.351899 -0.080556 -1.438341 0.865813 -0.001572 0.018786 0.979629 0.199929\n9289 47.360702 -0.080576 -1.438257 0.865922 -0.001666 0.019078 0.979620 0.199944\n9290 47.369973 -0.080595 -1.438437 0.865855 -0.000002 0.019088 0.979901 0.198569\n9291 47.376811 -0.081107 -1.438833 0.865653 -0.002270 0.021278 0.980026 0.197716\n9292 47.387445 -0.080632 -1.438423 0.865828 -0.001559 0.019486 0.979847 0.198791\n9293 47.395285 -0.080937 -1.438531 0.865749 -0.003265 0.020985 0.979850 0.198604\n9294 47.403220 -0.080838 -1.438899 0.865890 -0.001966 0.019745 0.979686 0.199554\n9295 47.411150 -0.080301 -1.438551 0.865575 -0.000433 0.018422 0.979751 0.199371\n9296 47.418902 -0.080620 -1.438571 0.865914 -0.001715 0.019617 0.979650 0.199746\n9297 47.427869 -0.080572 -1.438708 0.865594 -0.000760 0.018740 0.979822 0.198990\n9298 47.436700 -0.080530 -1.438602 0.865925 -0.001531 0.019120 0.979590 0.200089\n9299 47.443631 -0.080895 -1.438575 0.865767 -0.003023 0.020933 0.979817 0.198776\n9300 47.451882 -0.080754 -1.438667 0.865778 -0.002484 0.020398 0.979803 0.198909\n9301 47.461794 -0.080772 -1.438372 0.865825 -0.002423 0.020254 0.979823 0.198824\n9302 47.469874 -0.080556 -1.438452 0.865818 -0.001275 0.019250 0.979834 0.198878\n9303 47.478275 -0.080753 -1.438326 0.865783 -0.002832 0.020626 0.979830 0.198744\n9304 47.486457 -0.080539 -1.437998 0.866038 -0.001970 0.019168 0.979567 0.200196\n9305 47.493646 -0.080737 -1.438753 0.865406 -0.000786 0.019107 0.979672 0.199691\n9306 47.503252 -0.080790 -1.438416 0.865421 -0.001104 0.019360 0.979724 0.199409\n9307 47.511016 -0.080618 -1.438453 0.865947 -0.001188 0.019192 0.979726 0.199417\n9308 47.519955 -0.080532 -1.438543 0.865952 -0.001469 0.019394 0.979627 0.199884\n9309 47.526874 -0.080542 -1.438203 0.865842 -0.001211 0.019355 0.979849 0.198795\n9310 47.536436 -0.080597 -1.438439 0.865808 -0.001409 0.019442 0.979839 0.198837\n9311 47.544155 -0.080923 -1.438548 0.865735 -0.003101 0.020964 0.979849 0.198611\n9312 47.553825 -0.080868 -1.438593 0.865742 -0.002871 0.020803 0.979844 0.198658\n9313 47.561556 -0.080991 -1.438679 0.865591 -0.001682 0.020959 0.980054 0.197616\n9314 47.568882 -0.080895 -1.438577 0.865730 -0.002961 0.020939 0.979851 0.198608\n9315 47.579018 -0.081162 -1.438902 0.865638 -0.002447 0.021437 0.980006 0.197795\n9316 47.586660 -0.080839 -1.438905 0.865855 -0.001901 0.019782 0.979673 0.199612\n9317 47.594711 -0.080475 -1.438426 0.865862 -0.001588 0.018446 0.979517 0.200510\n9318 47.603483 -0.080599 -1.438442 0.865796 0.000340 0.019358 0.979918 0.198457\n9319 47.610450 -0.080483 -1.438649 0.865786 -0.001405 0.019579 0.979747 0.199277\n9320 47.619823 -0.081008 -1.438668 0.865608 -0.002341 0.021418 0.980011 0.197775\n9321 47.629263 -0.080643 -1.438409 0.865789 -0.001605 0.019653 0.979843 0.198795\n9322 47.637957 -0.080771 -1.438240 0.865400 -0.001215 0.019567 0.979729 0.199364\n9323 47.644930 -0.081063 -1.438774 0.865604 -0.002188 0.021384 0.980021 0.197730\n9324 47.653565 -0.080670 -1.438858 0.865752 -0.002045 0.020043 0.979727 0.199322\n9325 47.661782 -0.080910 -1.438608 0.865725 -0.002947 0.021052 0.979815 0.198774\n9326 47.669035 -0.080914 -1.438511 0.865721 -0.003094 0.020935 0.979835 0.198684\n9327 47.676786 -0.080676 -1.438324 0.865819 -0.001660 0.019843 0.979820 0.198888\n9328 47.686929 -0.080820 -1.438355 0.865365 -0.001278 0.019446 0.979652 0.199753\n9329 47.695091 -0.080954 -1.438489 0.865699 -0.003357 0.021182 0.979838 0.198642\n9330 47.703210 -0.080471 -1.438826 0.865797 -0.001344 0.019448 0.979668 0.199676\n9331 47.710035 -0.080420 -1.438773 0.865437 0.000040 0.018825 0.979827 0.198961\n9332 47.719761 -0.080918 -1.438559 0.865711 -0.003020 0.021036 0.979845 0.198627\n9333 47.726932 -0.080662 -1.438904 0.865388 -0.000354 0.019132 0.979723 0.199439\n9334 47.737115 -0.080739 -1.438063 0.865466 -0.001689 0.020194 0.979704 0.199424\n9335 47.744958 -0.080792 -1.438344 0.865766 -0.002499 0.020506 0.979837 0.198729\n9336 47.753337 -0.080624 -1.438529 0.865429 -0.000619 0.019506 0.979821 0.198924\n9337 47.761153 -0.081072 -1.438803 0.865592 -0.002127 0.021419 0.980021 0.197726\n9338 47.768670 -0.080752 -1.438376 0.865746 -0.002261 0.020271 0.979838 0.198749\n9339 47.778699 -0.080737 -1.438733 0.865717 -0.002280 0.020472 0.979802 0.198909\n9340 47.785603 -0.080447 -1.438689 0.865759 -0.001375 0.019541 0.979717 0.199428\n9341 47.794853 -0.080676 -1.438169 0.865454 -0.001476 0.019842 0.979674 0.199608\n9342 47.803731 -0.081055 -1.438772 0.865580 -0.001948 0.021332 0.980029 0.197698\n9343 47.810308 -0.080667 -1.438462 0.865767 -0.001334 0.019482 0.979670 0.199665\n9344 47.819903 -0.080814 -1.438584 0.865324 -0.001045 0.019340 0.979626 0.199897\n9345 47.827405 -0.080969 -1.438672 0.865585 -0.002135 0.021356 0.980001 0.197833\n9346 47.836599 -0.080656 -1.438375 0.865804 -0.001956 0.018776 0.979456 0.200775\n9347 47.843483 -0.080782 -1.438353 0.865743 -0.002389 0.020503 0.979836 0.198734\n9348 47.853075 -0.080864 -1.438770 0.865707 -0.002377 0.020753 0.979851 0.198634\n9349 47.860207 -0.080598 -1.438607 0.865770 -0.001452 0.019596 0.979724 0.199385\n9350 47.869873 -0.080756 -1.438364 0.865753 -0.002184 0.020366 0.979839 0.198738\n9351 47.878193 -0.080671 -1.438424 0.865766 -0.001546 0.019881 0.979847 0.198750\n9352 47.885123 -0.080656 -1.438454 0.865761 -0.001626 0.019866 0.979738 0.199287\n9353 47.893530 -0.080777 -1.438364 0.865742 -0.002355 0.020523 0.979837 0.198727\n9354 47.903474 -0.080435 -1.438662 0.865729 -0.000869 0.019119 0.979746 0.199330\n9355 47.910012 -0.080383 -1.438697 0.865730 -0.000898 0.018766 0.979632 0.199922\n9356 47.918482 -0.080448 -1.438794 0.865753 -0.001301 0.019567 0.979679 0.199610\n9357 47.926821 -0.081031 -1.438762 0.865569 -0.002037 0.021427 0.980014 0.197761\n9358 47.936818 -0.080786 -1.438347 0.865729 -0.002418 0.020616 0.979834 0.198732\n9359 47.945061 -0.080492 -1.438602 0.865743 -0.001403 0.019652 0.979761 0.199198\n9360 47.953435 -0.080560 -1.438452 0.865743 -0.001105 0.019540 0.979841 0.198817\n9361 47.960859 -0.080535 -1.438642 0.865880 -0.001365 0.019604 0.979607 0.199961\n9362 47.968491 -0.080370 -1.438387 0.865540 -0.001177 0.018156 0.979530 0.200477\n9363 47.978666 -0.080686 -1.438416 0.865750 -0.001618 0.020013 0.979850 0.198723\n9364 47.985572 -0.080878 -1.438745 0.865680 -0.002519 0.020952 0.979855 0.198592\n9365 47.994055 -0.080707 -1.438399 0.865692 -0.002493 0.020734 0.979819 0.198791\n9366 48.004277 -0.080548 -1.438524 0.865716 -0.001487 0.019948 0.979804 0.198958\n9367 48.011057 -0.080595 -1.438576 0.865738 -0.001456 0.019613 0.979706 0.199474\n9368 48.021553 -0.080445 -1.438852 0.865735 -0.001199 0.019478 0.979654 0.199743\n9369 48.027848 -0.080733 -1.438408 0.865740 -0.001797 0.020238 0.979828 0.198809\n9370 48.035696 -0.080507 -1.438800 0.865439 -0.000647 0.018982 0.979697 0.199584\n9371 48.044359 -0.080740 -1.438384 0.865729 -0.002024 0.020355 0.979842 0.198726\n9372 48.052977 -0.080566 -1.438658 0.865814 -0.001324 0.019425 0.979586 0.200083\n9373 48.060159 -0.080528 -1.438556 0.865717 -0.001427 0.019912 0.979793 0.199016\n9374 48.069757 -0.080457 -1.438168 0.865753 -0.001062 0.019583 0.979808 0.198979\n9375 48.077469 -0.080493 -1.438352 0.865710 -0.000817 0.019310 0.979843 0.198830\n9376 48.085172 -0.080955 -1.438649 0.865502 -0.001680 0.021303 0.980031 0.197695\n9377 48.094076 -0.080524 -1.438312 0.865564 -0.001583 0.018471 0.979501 0.200583\n9378 48.103635 -0.080624 -1.438616 0.865569 -0.001321 0.018631 0.979701 0.199591\n9379 48.111571 -0.080609 -1.438474 0.865712 -0.001673 0.020162 0.979820 0.198857\n9380 48.122188 -0.080803 -1.438902 0.865670 -0.002080 0.020710 0.979832 0.198734\n9381 48.127272 -0.080754 -1.438339 0.865680 -0.002709 0.021025 0.979817 0.198769\n9382 48.136631 -0.080556 -1.438479 0.865714 -0.001054 0.019566 0.979831 0.198866\n9383 48.144575 -0.080445 -1.438815 0.865726 -0.001182 0.019589 0.979668 0.199662\n9384 48.151812 -0.080805 -1.438365 0.865714 -0.002260 0.020813 0.979826 0.198751\n9385 48.161916 -0.080761 -1.438800 0.865677 -0.000717 0.019672 0.979873 0.198648\n9386 48.170011 -0.080285 -1.438450 0.865694 -0.000662 0.018820 0.979678 0.199693\n9387 48.178119 -0.080653 -1.438448 0.865706 -0.001709 0.020346 0.979828 0.198797\n9388 48.186455 -0.080562 -1.438516 0.865706 -0.001588 0.020072 0.979802 0.198954\n9389 48.193539 -0.080634 -1.438477 0.865696 -0.001526 0.020177 0.979826 0.198826\n9390 48.203116 -0.080616 -1.438292 0.865470 -0.001037 0.019296 0.979745 0.199313\n9391 48.210702 -0.080630 -1.438545 0.865774 -0.000889 0.019794 0.979736 0.199313\n9392 48.218504 -0.080735 -1.438440 0.865709 -0.001777 0.020245 0.979812 0.198886\n9393 48.226790 -0.080387 -1.438508 0.865467 -0.001080 0.018183 0.979505 0.200596\n9394 48.236380 -0.080722 -1.438403 0.865703 -0.001847 0.020346 0.979838 0.198745\n9395 48.244466 -0.080575 -1.438681 0.865523 -0.000912 0.020186 0.979866 0.198631\n9396 48.252962 -0.080508 -1.438622 0.865687 -0.000864 0.019390 0.979767 0.199200\n9397 48.261725 -0.080846 -1.438848 0.865638 -0.002203 0.020918 0.979843 0.198657\n9398 48.268595 -0.080955 -1.438681 0.865479 -0.001423 0.021209 0.980039 0.197665\n9399 48.278295 -0.080787 -1.438385 0.865631 -0.002731 0.021209 0.979821 0.198730\n9400 48.286450 -0.080431 -1.438758 0.865667 -0.000784 0.018897 0.979622 0.199957\n9401 48.295023 -0.080282 -1.438946 0.865638 0.000645 0.019838 0.979973 0.198137\n9402 48.303136 -0.080845 -1.438868 0.865631 -0.002201 0.021000 0.979854 0.198597\n9403 48.310327 -0.080779 -1.438392 0.865683 -0.002170 0.020638 0.979833 0.198740\n9404 48.319896 -0.080751 -1.438461 0.865256 -0.001024 0.019365 0.979551 0.200260\n9405 48.328225 -0.080585 -1.439037 0.865338 0.000186 0.019394 0.979806 0.199007\n9406 48.335296 -0.080480 -1.438233 0.865687 -0.000792 0.019468 0.979849 0.198788\n9407 48.344221 -0.080887 -1.438551 0.865428 -0.001293 0.021115 0.980033 0.197708\n9408 48.353716 -0.080799 -1.439194 0.865669 -0.001608 0.020532 0.979681 0.199501\n9409 48.360572 -0.080608 -1.438453 0.865692 -0.001207 0.019846 0.979833 0.198824\n9410 48.369982 -0.080812 -1.438360 0.865670 -0.002426 0.020882 0.979812 0.198813\n9411 48.377942 -0.080796 -1.438722 0.865634 -0.002395 0.021011 0.979774 0.198985\n9412 48.385268 -0.080469 -1.438272 0.865649 -0.000755 0.019396 0.979820 0.198936\n9413 48.394063 -0.080873 -1.438490 0.865457 -0.001583 0.021325 0.979998 0.197856\n9414 48.403636 -0.080595 -1.438494 0.865667 -0.001544 0.020117 0.979811 0.198904\n9415 48.410288 -0.080550 -1.438480 0.865669 -0.000987 0.019589 0.979827 0.198881\n9416 48.418578 -0.080774 -1.438859 0.865632 -0.001945 0.020673 0.979808 0.198861\n9417 48.428601 -0.080620 -1.438498 0.865672 -0.001232 0.019823 0.979811 0.198939\n9418 48.436259 -0.080400 -1.438734 0.865649 -0.000959 0.019598 0.979693 0.199540\n9419 48.444978 -0.080477 -1.438576 0.865614 -0.000598 0.019009 0.979727 0.199432\n9420 48.453821 -0.080533 -1.438416 0.865633 -0.001388 0.019732 0.979618 0.199892\n9421 48.460391 -0.080560 -1.438542 0.865591 -0.000872 0.019624 0.979701 0.199500\n9422 48.470074 -0.080672 -1.438235 0.865324 -0.001157 0.019849 0.979652 0.199715\n9423 48.478221 -0.080566 -1.438893 0.865311 -0.000040 0.019575 0.979771 0.199161\n9424 48.485180 -0.080748 -1.438864 0.865613 -0.002000 0.020815 0.979812 0.198822\n9425 48.494167 -0.080652 -1.438417 0.865644 -0.001645 0.020258 0.979825 0.198820\n9426 48.503765 -0.080745 -1.438776 0.865611 -0.002156 0.020819 0.979755 0.199104\n9427 48.510327 -0.080510 -1.438374 0.865459 -0.001137 0.020105 0.979646 0.199723\n9428 48.519915 -0.080748 -1.438424 0.865658 -0.001882 0.020540 0.979826 0.198787\n9429 48.527760 -0.080663 -1.438580 0.865337 -0.001248 0.018762 0.979508 0.200523\n9430 48.535240 -0.080649 -1.438463 0.865643 -0.001623 0.020348 0.979824 0.198819\n9431 48.543962 -0.080740 -1.438396 0.865656 -0.001986 0.020630 0.979834 0.198736\n9432 48.553582 -0.080570 -1.438509 0.865653 -0.001490 0.020335 0.979807 0.198905\n9433 48.560388 -0.080778 -1.438372 0.865645 -0.002234 0.020954 0.979829 0.198724\n9434 48.568610 -0.080745 -1.438389 0.865630 -0.002009 0.020760 0.979833 0.198728\n9435 48.578308 -0.080569 -1.438248 0.865443 -0.001373 0.020352 0.979641 0.199719\n9436 48.586089 -0.080589 -1.438456 0.865656 -0.001119 0.019932 0.979836 0.198803\n9437 48.595071 -0.080573 -1.438367 0.865342 -0.000931 0.019762 0.979619 0.199886\n9438 48.603631 -0.080626 -1.438503 0.865651 -0.001113 0.019988 0.979831 0.198822\n9439 48.610363 -0.080586 -1.438506 0.865765 -0.001341 0.020118 0.979663 0.199637\n9440 48.620047 -0.080620 -1.438442 0.865656 -0.001221 0.020122 0.979842 0.198756\n9441 48.628226 -0.080847 -1.438453 0.865418 -0.001527 0.021395 0.979997 0.197853\n9442 48.635269 -0.080810 -1.438822 0.865593 -0.002240 0.021154 0.979842 0.198638\n9443 48.644043 -0.080605 -1.438535 0.865711 -0.000818 0.019938 0.979724 0.199353\n9444 48.653210 -0.080668 -1.438429 0.865652 -0.001479 0.020282 0.979837 0.198761\n9445 48.660174 -0.080735 -1.438400 0.865639 -0.001932 0.020690 0.979832 0.198740\n9446 48.669645 -0.080884 -1.438579 0.865392 -0.001201 0.021157 0.980036 0.197688\n9447 48.677779 -0.080577 -1.438443 0.865634 -0.001078 0.019980 0.979838 0.198788\n9448 48.687219 -0.080770 -1.438798 0.865589 -0.002106 0.020960 0.979816 0.198787\n9449 48.694945 -0.080492 -1.438569 0.865790 -0.001159 0.019902 0.979611 0.199914\n9450 48.702915 -0.080627 -1.438478 0.865626 -0.001633 0.020498 0.979816 0.198841\n9451 48.711339 -0.080526 -1.438755 0.865425 -0.000472 0.019929 0.979858 0.198698\n9452 48.719898 -0.080533 -1.438433 0.865818 -0.001081 0.019908 0.979657 0.199689\n9453 48.728163 -0.080734 -1.438403 0.865634 -0.001905 0.020618 0.979830 0.198756\n9454 48.737156 -0.080697 -1.438424 0.865616 -0.001799 0.020626 0.979828 0.198765\n9455 48.743702 -0.080671 -1.438460 0.865648 -0.001339 0.020227 0.979817 0.198866\n9456 48.751936 -0.080730 -1.438490 0.865233 -0.000850 0.019768 0.979617 0.199899\n9457 48.760061 -0.080649 -1.438443 0.865607 -0.002042 0.020994 0.979814 0.198797\n9458 48.768651 -0.080498 -1.438502 0.865803 -0.001074 0.019857 0.979630 0.199823\n9459 48.779103 -0.080531 -1.438616 0.865619 -0.000640 0.019537 0.979789 0.199076\n9460 48.786447 -0.080523 -1.438620 0.865791 -0.001159 0.019887 0.979611 0.199914\n9461 48.794712 -0.080654 -1.438786 0.865305 -0.000768 0.019752 0.979677 0.199604\n9462 48.802957 -0.080552 -1.438385 0.865344 -0.000828 0.019838 0.979626 0.199845\n9463 48.810299 -0.080849 -1.438732 0.865575 -0.002388 0.021258 0.979837 0.198652\n9464 48.820256 -0.080496 -1.438633 0.865746 -0.001065 0.019691 0.979583 0.200069\n9465 48.827687 -0.080766 -1.438853 0.865576 -0.002055 0.021071 0.979820 0.198757\n9466 48.835092 -0.080435 -1.438406 0.865708 -0.001314 0.018967 0.979490 0.200593\n9467 48.844457 -0.080586 -1.438248 0.865323 -0.001094 0.020124 0.979637 0.199762\n9468 48.853277 -0.080760 -1.438380 0.865611 -0.002124 0.020880 0.979826 0.198748\n9469 48.860258 -0.080631 -1.438307 0.865296 -0.001045 0.019964 0.979625 0.199837\n9470 48.869128 -0.080885 -1.438539 0.865382 -0.001351 0.021423 0.980022 0.197726\n9471 48.878275 -0.080557 -1.438268 0.865620 -0.001225 0.020016 0.979824 0.198855\n9472 48.886742 -0.080440 -1.438509 0.865649 -0.001089 0.019122 0.979544 0.200316\n9473 48.894892 -0.080598 -1.438194 0.865313 -0.001145 0.020133 0.979655 0.199672\n9474 48.902256 -0.080561 -1.438218 0.865377 -0.001035 0.020369 0.979684 0.199509\n9475 48.910332 -0.080821 -1.438738 0.865554 -0.002379 0.021287 0.979828 0.198693\n9476 48.918804 -0.080737 -1.438411 0.865617 -0.001800 0.020693 0.979828 0.198758\n9477 48.930060 -0.080566 -1.438535 0.865786 -0.001083 0.019921 0.979629 0.199821\n9478 48.935951 -0.080853 -1.438700 0.865546 -0.002484 0.021356 0.979829 0.198676\n9479 48.943655 -0.080509 -1.438351 0.865384 -0.001008 0.020143 0.979643 0.199732\n9480 48.953446 -0.080541 -1.438487 0.865602 -0.000852 0.019875 0.979821 0.198884\n9481 48.961807 -0.080673 -1.438438 0.865619 -0.001454 0.020347 0.979830 0.198791\n9482 48.968856 -0.080368 -1.438793 0.865596 -0.000776 0.019625 0.979661 0.199699\n9483 48.978496 -0.080494 -1.438523 0.865595 -0.000655 0.019617 0.979811 0.198959\n9484 48.986003 -0.080320 -1.438740 0.865583 -0.000569 0.019285 0.979680 0.199638\n9485 48.993559 -0.080587 -1.438334 0.865286 -0.000871 0.019857 0.979618 0.199884\n9486 49.003802 -0.080567 -1.438526 0.865594 -0.001378 0.020333 0.979799 0.198944\n9487 49.011250 -0.080779 -1.438680 0.865563 -0.002287 0.021153 0.979768 0.199004\n9488 49.019938 -0.080621 -1.438137 0.865263 -0.001087 0.020151 0.979663 0.199631\n9489 49.028420 -0.080437 -1.438814 0.865608 -0.000971 0.019921 0.979673 0.199606\n9490 49.037089 -0.080432 -1.438644 0.865590 -0.000974 0.019969 0.979746 0.199243\n9491 49.044580 -0.080710 -1.438751 0.865643 -0.001060 0.019923 0.979577 0.200078\n9492 49.054154 -0.080685 -1.438431 0.865525 -0.001312 0.020296 0.979825 0.198822\n9493 49.061558 -0.080538 -1.438502 0.865599 -0.000808 0.019844 0.979819 0.198896\n9494 49.070831 -0.080510 -1.438543 0.865752 -0.001064 0.019971 0.979609 0.199917\n9495 49.077316 -0.080810 -1.438376 0.865588 -0.002217 0.021161 0.979808 0.198807\n9496 49.087171 -0.080625 -1.438485 0.865590 -0.001420 0.020440 0.979813 0.198862\n9497 49.094858 -0.080783 -1.438802 0.865549 -0.002030 0.021107 0.979819 0.198759\n9498 49.101755 -0.080740 -1.438895 0.865544 -0.001871 0.021041 0.979805 0.198837\n9499 49.112416 -0.080729 -1.438827 0.865638 -0.001057 0.019999 0.979618 0.199871\n9500 49.119141 -0.080688 -1.438431 0.865561 -0.002211 0.021184 0.979802 0.198835\n9501 49.128269 -0.080743 -1.438913 0.865541 -0.001821 0.021041 0.979813 0.198800\n9502 49.135365 -0.080520 -1.438581 0.865392 -0.000720 0.019309 0.979645 0.199807\n9503 49.143692 -0.080570 -1.438272 0.865342 -0.000906 0.020265 0.979661 0.199631\n9504 49.152954 -0.080572 -1.438704 0.865370 -0.000580 0.019364 0.979668 0.199688\n9505 49.161033 -0.080525 -1.438788 0.865436 -0.000504 0.020189 0.979853 0.198696\n9506 49.170472 -0.080757 -1.438392 0.865589 -0.001958 0.020983 0.979826 0.198741\n9507 49.177573 -0.080652 -1.438413 0.865228 -0.000802 0.019918 0.979611 0.199913\n9508 49.186417 -0.080604 -1.438797 0.865457 -0.000242 0.020038 0.979811 0.198917\n9509 49.194576 -0.080489 -1.438598 0.865580 -0.001096 0.020132 0.979762 0.199145\n9510 49.202093 -0.080789 -1.438707 0.865539 -0.002299 0.021285 0.979771 0.198973\n9511 49.210492 -0.080791 -1.438932 0.865547 -0.001772 0.021084 0.979775 0.198981\n9512 49.220537 -0.080708 -1.438412 0.865594 -0.001691 0.020706 0.979827 0.198764\n9513 49.228077 -0.080495 -1.438578 0.865574 -0.001101 0.020223 0.979775 0.199075\n9514 49.236245 -0.080496 -1.438420 0.865557 -0.001167 0.019984 0.979613 0.199892\n9515 49.244885 -0.080692 -1.438146 0.865219 -0.001050 0.020201 0.979669 0.199598\n9516 49.251788 -0.080579 -1.438484 0.865587 -0.000923 0.020073 0.979825 0.198845\n9517 49.261646 -0.080432 -1.438641 0.865546 -0.000373 0.019424 0.979778 0.199145\n9518 49.269943 -0.080663 -1.438452 0.865578 -0.001249 0.020367 0.979828 0.198801\n9519 49.278139 -0.080659 -1.438449 0.865586 -0.001281 0.020402 0.979829 0.198791\n9520 49.286733 -0.080379 -1.438690 0.865334 -0.000172 0.019294 0.979734 0.199371\n9521 49.294208 -0.080769 -1.438841 0.865521 -0.002033 0.021213 0.979812 0.198784\n9522 49.301832 -0.080722 -1.438406 0.865581 -0.001732 0.020741 0.979825 0.198772\n9523 49.310088 -0.080730 -1.438434 0.865581 -0.001624 0.020740 0.979797 0.198909\n9524 49.319867 -0.080617 -1.438022 0.865267 -0.001199 0.020520 0.979722 0.199303\n9525 49.327361 -0.080875 -1.438572 0.865327 -0.001063 0.021360 0.980034 0.197676\n9526 49.337164 -0.080617 -1.438465 0.865578 -0.001061 0.020222 0.979827 0.198820\n9527 49.343969 -0.080815 -1.438371 0.865549 -0.002325 0.021344 0.979801 0.198819\n9528 49.351777 -0.080842 -1.438460 0.865362 -0.001511 0.021680 0.979986 0.197879\n9529 49.360938 -0.080629 -1.438481 0.865559 -0.001478 0.020666 0.979811 0.198849\n9530 49.370075 -0.080431 -1.438460 0.865374 -0.000837 0.018921 0.979557 0.200274\n9531 49.376845 -0.080616 -1.438454 0.865557 -0.001409 0.020635 0.979811 0.198854\n9532 49.385095 -0.080729 -1.438415 0.865571 -0.001786 0.020845 0.979822 0.198775\n9533 49.395456 -0.080832 -1.438755 0.865510 -0.002264 0.021442 0.979827 0.198680\n9534 49.402584 -0.080559 -1.438189 0.865327 -0.001193 0.020540 0.979666 0.199576\n9535 49.411363 -0.080738 -1.438468 0.865573 -0.001708 0.020782 0.979791 0.198932\n9536 49.420672 -0.080577 -1.438673 0.865229 -0.000187 0.019836 0.979713 0.199423\n9537 49.426920 -0.080760 -1.438239 0.865145 -0.000996 0.020023 0.979602 0.199945\n9538 49.435408 -0.080743 -1.438999 0.865274 0.000247 0.020687 0.979909 0.198370\n9539 49.445342 -0.080511 -1.438572 0.865556 -0.001016 0.020119 0.979777 0.199074\n9540 49.453124 -0.080698 -1.438429 0.865572 -0.001541 0.020687 0.979826 0.198775\n9541 49.461439 -0.080463 -1.438623 0.865577 -0.000724 0.019473 0.979596 0.200032\n9542 49.469992 -0.080868 -1.438504 0.865360 -0.001594 0.021762 0.979986 0.197869\n9543 49.476977 -0.080611 -1.438468 0.865570 -0.001060 0.020245 0.979827 0.198819\n9544 49.487119 -0.080830 -1.438491 0.865355 -0.001353 0.021567 0.979995 0.197843\n9545 49.494395 -0.080600 -1.438555 0.865498 -0.000678 0.020082 0.979712 0.199399\n9546 49.501918 -0.080732 -1.438929 0.865507 -0.001735 0.021100 0.979801 0.198851\n9547 49.511147 -0.080480 -1.438656 0.865551 -0.000990 0.020051 0.979697 0.199475\n9548 49.520198 -0.080364 -1.438221 0.865580 -0.000548 0.019836 0.979740 0.199288\n9549 49.526891 -0.080583 -1.438475 0.865555 -0.000955 0.020152 0.979826 0.198832\n9550 49.537559 -0.080615 -1.438504 0.865557 -0.000905 0.020178 0.979803 0.198940\n9551 49.544864 -0.080841 -1.438463 0.865340 -0.001531 0.021729 0.979986 0.197873\n9552 49.551768 -0.080360 -1.438301 0.865630 -0.001174 0.018924 0.979458 0.200756\n9553 49.562236 -0.080569 -1.438266 0.865254 -0.000901 0.020275 0.979649 0.199691\n9554 49.569387 -0.080683 -1.438446 0.865555 -0.001382 0.020609 0.979827 0.198776\n9555 49.578318 -0.080668 -1.439103 0.865523 -0.001404 0.020685 0.979705 0.199370\n9556 49.586969 -0.080660 -1.438469 0.865503 -0.000881 0.020075 0.979807 0.198933\n9557 49.593947 -0.080771 -1.438744 0.865505 -0.002167 0.021336 0.979765 0.199002\n9558 49.602273 -0.080493 -1.438464 0.865541 -0.000556 0.019798 0.979819 0.198902\n9559 49.611691 -0.080744 -1.438415 0.865548 -0.001809 0.020959 0.979823 0.198759\n9560 49.619050 -0.080574 -1.438522 0.865535 -0.000817 0.020052 0.979812 0.198911\n9561 49.627853 -0.080390 -1.438717 0.865410 0.000043 0.019806 0.979811 0.198943\n9562 49.636296 -0.080302 -1.438761 0.865513 -0.000455 0.019475 0.979650 0.199766\n9563 49.644633 -0.080809 -1.438800 0.865500 -0.002048 0.021368 0.979819 0.198731\n9564 49.653811 -0.080446 -1.438642 0.865538 -0.000963 0.020196 0.979739 0.199258\n9565 49.660704 -0.080488 -1.438383 0.865589 -0.001206 0.019175 0.979471 0.200669\n9566 49.668766 -0.080861 -1.438654 0.865483 -0.002541 0.021680 0.979784 0.198862\n9567 49.677688 -0.080458 -1.438497 0.865542 -0.001008 0.019130 0.979508 0.200494\n9568 49.686667 -0.080810 -1.438752 0.865484 -0.002235 0.021442 0.979815 0.198743\n9569 49.693673 -0.080556 -1.438401 0.865215 -0.000604 0.019959 0.979624 0.199845\n9570 49.701828 -0.080893 -1.438601 0.865305 -0.001129 0.021556 0.980026 0.197693\n9571 49.711552 -0.080761 -1.438410 0.865538 -0.001825 0.021020 0.979802 0.198856\n9572 49.719684 -0.080837 -1.438496 0.865322 -0.001409 0.021716 0.979980 0.197902\n9573 49.730072 -0.080483 -1.438492 0.865515 -0.000462 0.019791 0.979815 0.198925\n9574 49.735737 -0.080487 -1.438457 0.865516 -0.001083 0.020044 0.979614 0.199882\n9575 49.743545 -0.080656 -1.438454 0.865543 -0.001246 0.020549 0.979824 0.198798\n9576 49.752242 -0.080756 -1.438408 0.865537 -0.001873 0.021009 0.979815 0.198792\n9577 49.761148 -0.080832 -1.438611 0.865473 -0.002594 0.021650 0.979776 0.198907\n9578 49.768623 -0.080884 -1.438620 0.865457 -0.002733 0.021844 0.979785 0.198837\n9579 49.778936 -0.080701 -1.438450 0.865513 -0.001589 0.020780 0.979816 0.198813\n9580 49.786037 -0.080429 -1.438683 0.865505 -0.000626 0.020007 0.979735 0.199298\n9581 49.793589 -0.080404 -1.438405 0.865477 -0.000156 0.019273 0.979791 0.199095\n9582 49.803064 -0.080793 -1.438809 0.865478 -0.002084 0.021458 0.979775 0.198940\n9583 49.811246 -0.080682 -1.438635 0.865374 -0.001171 0.019287 0.979653 0.199769\n9584 49.820422 -0.080587 -1.438514 0.865528 -0.000837 0.020222 0.979798 0.198963\n9585 49.828320 -0.080637 -1.438462 0.865516 -0.000917 0.020152 0.979723 0.199340\n9586 49.837193 -0.080425 -1.438701 0.865514 -0.000824 0.020215 0.979720 0.199350\n9587 49.844404 -0.080566 -1.438483 0.865466 -0.000750 0.019916 0.979667 0.199639\n9588 49.852839 -0.080497 -1.438582 0.865514 -0.001019 0.020388 0.979774 0.199062\n9589 49.861278 -0.080621 -1.438531 0.865535 -0.001092 0.020387 0.979786 0.199003\n9590 49.870094 -0.080416 -1.438937 0.865516 -0.000581 0.019870 0.979620 0.199873\n9591 49.877151 -0.080636 -1.438488 0.865513 -0.001390 0.020692 0.979809 0.198859\n9592 49.885349 -0.080483 -1.438504 0.865543 -0.000965 0.019422 0.979529 0.200362\n9593 49.894768 -0.080709 -1.438438 0.865527 -0.001522 0.020740 0.979820 0.198798\n9594 49.902888 -0.080687 -1.438470 0.865525 -0.001139 0.020510 0.979815 0.198849\n9595 49.910026 -0.080520 -1.438579 0.865512 -0.001118 0.020388 0.979772 0.199074\n9596 49.920105 -0.080583 -1.438254 0.865312 -0.000998 0.020768 0.979658 0.199594\n9597 49.928362 -0.080740 -1.438876 0.865462 -0.001823 0.021256 0.979802 0.198830\n9598 49.935286 -0.080660 -1.438482 0.865524 -0.001084 0.020443 0.979802 0.198917\n9599 49.946690 -0.080750 -1.438436 0.865516 -0.001710 0.020939 0.979815 0.198802\n9600 49.952510 -0.080822 -1.438772 0.865456 -0.002268 0.021574 0.979818 0.198714\n9601 49.962140 -0.080729 -1.438871 0.865472 -0.001763 0.021213 0.979793 0.198879\n9602 49.969355 -0.080490 -1.438620 0.865589 -0.000762 0.019769 0.979586 0.200050\n9603 49.977982 -0.080762 -1.438775 0.865467 -0.001983 0.021334 0.979759 0.199030\n9604 49.986479 -0.080346 -1.438701 0.865491 -0.000428 0.019502 0.979659 0.199721\n9605 49.994977 -0.080680 -1.439106 0.865477 -0.001305 0.020832 0.979733 0.199219\n9606 50.003780 -0.080686 -1.438465 0.865495 -0.001486 0.020839 0.979813 0.198822\n9607 50.011693 -0.080399 -1.438639 0.865495 -0.000570 0.019827 0.979738 0.199298\n9608 50.021188 -0.080776 -1.438123 0.865384 -0.002004 0.021659 0.979742 0.199077\n9609 50.028457 -0.080616 -1.438503 0.865498 -0.001282 0.020641 0.979804 0.198890\n9610 50.035940 -0.080499 -1.438624 0.865485 -0.000430 0.019857 0.979779 0.199092\n9611 50.044696 -0.080523 -1.438676 0.865297 -0.000660 0.019080 0.979695 0.199581\n9612 50.055022 -0.080747 -1.438801 0.865466 -0.001907 0.021316 0.979751 0.199071\n9613 50.061019 -0.080698 -1.438879 0.865464 -0.001688 0.021109 0.979776 0.198976\n9614 50.070321 -0.080755 -1.438409 0.865500 -0.001880 0.021140 0.979815 0.198779\n9615 50.077553 -0.080791 -1.438823 0.865450 -0.001979 0.021427 0.979811 0.198764\n9616 50.086923 -0.080703 -1.438446 0.865486 -0.001555 0.020892 0.979815 0.198805\n9617 50.094689 -0.080797 -1.438724 0.865454 -0.002169 0.021540 0.979766 0.198972\n9618 50.101774 -0.080459 -1.438630 0.865498 -0.000845 0.020307 0.979747 0.199208\n9619 50.111044 -0.080696 -1.438466 0.865514 -0.001286 0.020691 0.979800 0.198903\n9620 50.120553 -0.080898 -1.438608 0.865431 -0.002817 0.022008 0.979778 0.198855\n9621 50.127752 -0.080742 -1.438392 0.865487 -0.002012 0.021224 0.979782 0.198932\n9622 50.135139 -0.080686 -1.438465 0.865494 -0.001514 0.020808 0.979811 0.198836\n9623 50.145747 -0.080486 -1.438310 0.865688 -0.001358 0.019600 0.979444 0.200757\n9624 50.152559 -0.080751 -1.439047 0.865445 -0.001511 0.021207 0.979794 0.198877\n9625 50.161457 -0.080551 -1.438553 0.865491 -0.000570 0.020063 0.979790 0.199019\n9626 50.170738 -0.080919 -1.438452 0.865320 -0.001809 0.022044 0.979933 0.198097\n9627 50.177593 -0.080677 -1.439068 0.865459 -0.001323 0.020938 0.979745 0.199150\n9628 50.186420 -0.080452 -1.438514 0.865462 -0.000092 0.019504 0.979799 0.199031\n9629 50.194311 -0.080527 -1.438349 0.865679 -0.000538 0.020177 0.979683 0.199536\n9630 50.201880 -0.080555 -1.438208 0.865252 -0.000753 0.020631 0.979704 0.199385\n9631 50.210328 -0.080817 -1.438965 0.865441 -0.001703 0.021453 0.979831 0.198664\n9632 50.219383 -0.080779 -1.438399 0.865482 -0.002037 0.021378 0.979809 0.198781\n9633 50.228288 -0.080740 -1.438437 0.865503 -0.001558 0.020995 0.979818 0.198781\n9634 50.235040 -0.080627 -1.438504 0.865502 -0.000938 0.020435 0.979797 0.198945\n9635 50.245603 -0.080857 -1.438680 0.865439 -0.002426 0.021762 0.979775 0.198899\n9636 50.252555 -0.080692 -1.438468 0.865493 -0.001177 0.020659 0.979821 0.198804\n9637 50.261558 -0.080802 -1.438762 0.865447 -0.002087 0.021564 0.979768 0.198959\n9638 50.269529 -0.080414 -1.438683 0.865476 -0.000307 0.019732 0.979650 0.199742\n9639 50.278261 -0.080607 -1.438249 0.865302 -0.001095 0.020994 0.979661 0.199558\n9640 50.285149 -0.080770 -1.438433 0.865457 -0.002389 0.021657 0.979766 0.198955\n9641 50.295067 -0.080548 -1.438316 0.865324 -0.001011 0.020872 0.979641 0.199666\n9642 50.302830 -0.080625 -1.438908 0.865342 0.000167 0.020303 0.979792 0.198986\n9643 50.311618 -0.080608 -1.438517 0.865500 -0.000835 0.020390 0.979793 0.198972\n9644 50.319436 -0.080446 -1.438529 0.865424 -0.000312 0.019776 0.979683 0.199572\n9645 50.328189 -0.080620 -1.438506 0.865497 -0.000865 0.020427 0.979798 0.198943\n9646 50.335343 -0.080720 -1.438644 0.865239 0.000283 0.020897 0.979929 0.198248\n9647 50.343469 -0.080868 -1.438724 0.865426 -0.002462 0.021905 0.979782 0.198849\n9648 50.353421 -0.080720 -1.438467 0.865479 -0.001618 0.020892 0.979808 0.198840\n9649 50.361947 -0.080557 -1.438555 0.865306 -0.000646 0.019564 0.979616 0.199923\n9650 50.370253 -0.080511 -1.438771 0.865333 -0.000014 0.020040 0.979742 0.199261\n9651 50.377438 -0.080507 -1.438705 0.865285 -0.000230 0.020261 0.979838 0.198763\n9652 50.385172 -0.080751 -1.438773 0.865447 -0.001933 0.021373 0.979752 0.199062\n9653 50.395623 -0.080414 -1.438808 0.865469 -0.000593 0.020188 0.979690 0.199500\n9654 50.402453 -0.080852 -1.438586 0.865235 -0.000792 0.021457 0.980030 0.197688\n9655 50.411542 -0.080512 -1.438345 0.865280 -0.000669 0.020614 0.979671 0.199549\n9656 50.419640 -0.080808 -1.438396 0.865466 -0.002114 0.021480 0.979790 0.198859\n9657 50.427718 -0.080223 -1.438664 0.865392 0.000054 0.019061 0.979698 0.199569\n9658 50.435190 -0.080851 -1.438467 0.865282 -0.001457 0.021878 0.979974 0.197915\n9659 50.445392 -0.080764 -1.438421 0.865479 -0.001850 0.021222 0.979812 0.198785\n9660 50.452493 -0.080712 -1.438450 0.865485 -0.001391 0.020784 0.979801 0.198887\n9661 50.461528 -0.080712 -1.438867 0.865311 -0.000053 0.020272 0.979797 0.198964\n9662 50.470199 -0.080614 -1.438515 0.865467 -0.001232 0.020692 0.979801 0.198896\n9663 50.478015 -0.080746 -1.438360 0.865368 -0.001333 0.019895 0.979522 0.200347\n9664 50.494064 -0.080546 -1.438481 0.865476 -0.000512 0.020309 0.979717 0.199352\n9665 50.494276 -0.080752 -1.438780 0.865432 -0.001927 0.021403 0.979746 0.199087\n9666 50.502326 -0.080874 -1.438651 0.865411 -0.002591 0.021958 0.979777 0.198866\n9667 50.510349 -0.080513 -1.438353 0.865275 -0.000696 0.020644 0.979675 0.199526\n9668 50.519210 -0.080544 -1.438548 0.865457 -0.000521 0.020060 0.979791 0.199017\n9669 50.527790 -0.080763 -1.438416 0.865473 -0.001899 0.021274 0.979808 0.198797\n9670 50.535225 -0.080511 -1.438571 0.865512 -0.000720 0.019783 0.979570 0.200125\n9671 50.546773 -0.080842 -1.438747 0.865418 -0.002177 0.021728 0.979780 0.198884\n9672 50.552313 -0.080748 -1.438429 0.865456 -0.001179 0.020663 0.979788 0.198966\n9673 50.560279 -0.080650 -1.438931 0.865397 0.000051 0.020300 0.979791 0.198990\n9674 50.569554 -0.080889 -1.438708 0.865404 -0.002493 0.022004 0.979783 0.198836\n9675 50.578363 -0.080370 -1.438938 0.865211 0.000151 0.018949 0.979760 0.199276\n9676 50.585423 -0.080574 -1.438538 0.865459 -0.000626 0.020191 0.979791 0.199002\n9677 50.595211 -0.080489 -1.438593 0.865221 -0.000047 0.019811 0.979763 0.199178\n9678 50.603075 -0.080780 -1.438879 0.865421 -0.001781 0.021454 0.979810 0.198769\n9679 50.611594 -0.080558 -1.438573 0.865463 -0.000676 0.020195 0.979777 0.199068\n9680 50.618953 -0.080861 -1.438702 0.865408 -0.002429 0.021864 0.979776 0.198884\n9681 50.627985 -0.080699 -1.438449 0.865475 -0.001292 0.020738 0.979798 0.198907\n9682 50.637174 -0.080743 -1.438625 0.865454 -0.000977 0.020474 0.979663 0.199599\n9683 50.644198 -0.080527 -1.438493 0.865441 -0.000392 0.019952 0.979800 0.198982\n9684 50.652284 -0.080672 -1.438288 0.865565 -0.001139 0.020553 0.979612 0.199843\n9685 50.661649 -0.080757 -1.438426 0.865417 -0.002381 0.021748 0.979783 0.198866\n9686 50.669207 -0.080873 -1.438724 0.865397 -0.002476 0.021989 0.979780 0.198848\n9687 50.678123 -0.080807 -1.438757 0.865415 -0.002132 0.021629 0.979766 0.198961\n9688 50.687259 -0.080854 -1.438821 0.865408 -0.002127 0.021803 0.979786 0.198846\n9689 50.694206 -0.080355 -1.438756 0.865437 -0.000131 0.019544 0.979713 0.199451\n9690 50.702304 -0.080683 -1.438352 0.865459 -0.000880 0.020526 0.979819 0.198828\n9691 50.711488 -0.080854 -1.438637 0.865401 -0.002539 0.021938 0.979767 0.198922\n9692 50.719073 -0.080664 -1.438476 0.865446 -0.001350 0.020952 0.979809 0.198833\n9693 50.727794 -0.080630 -1.438167 0.865254 -0.000989 0.021175 0.979726 0.199217\n9694 50.735848 -0.080579 -1.438524 0.865451 -0.000669 0.020269 0.979792 0.198990\n9695 50.744920 -0.080623 -1.438309 0.865618 -0.000880 0.020524 0.979597 0.199921\n9696 50.753390 -0.080547 -1.438334 0.865306 -0.000938 0.020987 0.979646 0.199631\n9697 50.761593 -0.080581 -1.438302 0.865303 -0.001170 0.021122 0.979625 0.199721\n9698 50.769157 -0.080487 -1.438510 0.865396 -0.000356 0.019940 0.979677 0.199590\n9699 50.778158 -0.080557 -1.438567 0.865451 -0.000597 0.020228 0.979784 0.199032\n9700 50.785886 -0.080806 -1.438395 0.865450 -0.002055 0.021477 0.979788 0.198871\n9701 50.795200 -0.080532 -1.438383 0.865553 -0.001085 0.019631 0.979484 0.200560\n9702 50.803098 -0.080474 -1.438369 0.865419 -0.000283 0.019854 0.979803 0.198980\n9703 50.811325 -0.080477 -1.438547 0.865417 -0.000243 0.019839 0.979785 0.199069\n9704 50.819020 -0.080586 -1.438557 0.865456 -0.000590 0.020279 0.979789 0.199001\n9705 50.826926 -0.080874 -1.438613 0.865383 -0.002693 0.022062 0.979769 0.198892\n9706 50.835978 -0.080727 -1.438749 0.865416 -0.001865 0.021366 0.979737 0.199137\n9707 50.845099 -0.080867 -1.438604 0.865391 -0.002658 0.021976 0.979764 0.198931\n9708 50.853621 -0.080687 -1.438461 0.865464 -0.001334 0.020807 0.979810 0.198840\n9709 50.860664 -0.080507 -1.438559 0.865464 -0.000949 0.020378 0.979656 0.199647\n9710 50.868694 -0.080709 -1.438785 0.865410 -0.001788 0.021330 0.979736 0.199146\n9711 50.878246 -0.080685 -1.438833 0.865406 -0.001665 0.021237 0.979776 0.198958\n9712 50.886059 -0.080313 -1.438805 0.865233 0.000539 0.019412 0.979736 0.199349\n9713 50.894977 -0.080835 -1.438684 0.865394 -0.002502 0.021944 0.979762 0.198943\n9714 50.902221 -0.080593 -1.438514 0.865435 -0.000688 0.020238 0.979795 0.198975\n9715 50.912406 -0.080590 -1.438573 0.865464 -0.001032 0.020550 0.979714 0.199341\n9716 50.918843 -0.080873 -1.438666 0.865369 -0.002654 0.022141 0.979766 0.198898\n9717 50.928193 -0.080894 -1.438559 0.865357 -0.002967 0.022214 0.979761 0.198911\n9718 50.936236 -0.080528 -1.438367 0.865313 -0.001002 0.021010 0.979630 0.199705\n9719 50.943975 -0.080436 -1.439056 0.865435 -0.000213 0.019958 0.979649 0.199722\n9720 50.952786 -0.080742 -1.438786 0.865399 -0.001932 0.021503 0.979786 0.198880\n9721 50.961119 -0.080684 -1.438495 0.865456 -0.001293 0.020868 0.979786 0.198951\n9722 50.968613 -0.080553 -1.438545 0.865424 -0.000545 0.020148 0.979790 0.199012\n9723 50.978438 -0.080768 -1.438968 0.865320 -0.000152 0.020349 0.979705 0.199410\n9724 50.985578 -0.080789 -1.438751 0.865397 -0.002087 0.021638 0.979797 0.198808\n9725 50.993491 -0.080391 -1.438757 0.865439 -0.000624 0.020231 0.979679 0.199550\n9726 51.003092 -0.080692 -1.438470 0.865457 -0.001188 0.020717 0.979794 0.198929\n9727 51.011271 -0.080470 -1.438804 0.865169 0.000710 0.020178 0.979829 0.198814\n9728 51.018471 -0.080802 -1.438766 0.865391 -0.002058 0.021609 0.979801 0.198793\n9729 51.027158 -0.080675 -1.439129 0.865415 -0.001215 0.021038 0.979727 0.199225\n9730 51.035917 -0.080496 -1.438726 0.865442 -0.000556 0.020201 0.979739 0.199259\n9731 51.045335 -0.080534 -1.438373 0.865309 -0.000946 0.020979 0.979631 0.199706\n9732 51.054788 -0.080512 -1.438557 0.865411 -0.000331 0.020007 0.979787 0.199042\n9733 51.061296 -0.080519 -1.438594 0.865436 -0.000939 0.020466 0.979764 0.199103\n9734 51.068793 -0.080836 -1.438606 0.865373 -0.002602 0.021905 0.979759 0.198964\n9735 51.078117 -0.080631 -1.439220 0.865449 -0.000972 0.020597 0.979616 0.199820\n9736 51.086024 -0.080514 -1.438416 0.865323 -0.000969 0.020996 0.979630 0.199710\n9737 51.095142 -0.080583 -1.438703 0.865229 -0.000526 0.019408 0.979693 0.199560\n9738 51.102296 -0.080698 -1.438496 0.865443 -0.001401 0.020898 0.979798 0.198892\n9739 51.112360 -0.080433 -1.438651 0.865387 -0.000350 0.019750 0.979623 0.199874\n9740 51.119529 -0.080835 -1.438627 0.865373 -0.002556 0.021989 0.979762 0.198937\n9741 51.128123 -0.080659 -1.438496 0.865435 -0.000974 0.020573 0.979793 0.198951\n9742 51.136056 -0.080386 -1.438746 0.865435 -0.000646 0.020285 0.979677 0.199554\n9743 51.144945 -0.080851 -1.438617 0.865371 -0.002599 0.021998 0.979763 0.198934\n9744 51.152463 -0.080453 -1.438316 0.865452 -0.000380 0.020436 0.979747 0.199196\n9745 51.161711 -0.080750 -1.438444 0.865436 -0.001771 0.021266 0.979802 0.198828\n9746 51.168803 -0.080848 -1.438574 0.865364 -0.002735 0.022009 0.979756 0.198966\n9747 51.177719 -0.080707 -1.438900 0.865382 -0.001593 0.021344 0.979776 0.198949\n9748 51.186612 -0.080904 -1.438510 0.865343 -0.003068 0.022291 0.979761 0.198902\n9749 51.194914 -0.080588 -1.438266 0.865261 -0.000965 0.021188 0.979676 0.199462\n9750 51.203892 -0.080673 -1.438554 0.865449 -0.001252 0.020843 0.979752 0.199123\n9751 51.211346 -0.080445 -1.438338 0.865400 -0.000285 0.019946 0.979795 0.199005\n9752 51.219023 -0.080636 -1.438507 0.865439 -0.000869 0.020467 0.979791 0.198973\n9753 51.228168 -0.080469 -1.438626 0.865392 -0.000068 0.019747 0.979781 0.199095\n9754 51.236926 -0.080784 -1.438641 0.865383 -0.002306 0.021746 0.979750 0.199027\n9755 51.244401 -0.080657 -1.438477 0.865445 -0.001184 0.020736 0.979804 0.198878\n9756 51.251935 -0.080655 -1.438347 0.865415 -0.001031 0.020663 0.979805 0.198880\n9757 51.261952 -0.080708 -1.438458 0.865433 -0.001312 0.020892 0.979792 0.198922\n9758 51.269383 -0.080575 -1.438541 0.865420 -0.000612 0.020318 0.979788 0.199003\n9759 51.278290 -0.080627 -1.438208 0.865237 -0.000931 0.021323 0.979722 0.199221\n9760 51.285894 -0.080398 -1.438851 0.865137 0.000777 0.019926 0.979791 0.199027\n9761 51.294693 -0.080674 -1.438963 0.865410 -0.001323 0.021066 0.979667 0.199518\n9762 51.302757 -0.080691 -1.438737 0.865382 -0.001813 0.021426 0.979730 0.199166\n9763 51.311546 -0.080781 -1.438637 0.865377 -0.002262 0.021723 0.979746 0.199052\n9764 51.319232 -0.080533 -1.438645 0.865341 0.000247 0.020233 0.979811 0.198901\n9765 51.327790 -0.080656 -1.438486 0.865433 -0.001029 0.020605 0.979791 0.198960\n9766 51.336186 -0.080736 -1.438648 0.865375 -0.002113 0.021587 0.979742 0.199085\n9767 51.344980 -0.080570 -1.438318 0.865263 -0.000983 0.021146 0.979641 0.199639\n9768 51.354122 -0.080792 -1.438403 0.865415 -0.001946 0.021385 0.979782 0.198910\n9769 51.360751 -0.080606 -1.438566 0.865575 -0.000093 0.020197 0.979736 0.199275\n9770 51.368815 -0.080692 -1.439135 0.865440 -0.001105 0.020527 0.979511 0.200338\n9771 51.377598 -0.080694 -1.438862 0.865384 -0.001517 0.021266 0.979728 0.199194\n9772 51.386251 -0.080390 -1.438832 0.865425 -0.000609 0.020252 0.979639 0.199740\n9773 51.394903 -0.080626 -1.438499 0.865423 -0.000903 0.020559 0.979791 0.198964\n9774 51.402006 -0.080472 -1.438275 0.865193 -0.000639 0.020696 0.979698 0.199406\n9775 51.411638 -0.080738 -1.438678 0.865373 -0.002100 0.021636 0.979746 0.199061\n9776 51.419557 -0.080527 -1.438545 0.865409 -0.000448 0.020198 0.979802 0.198950\n9777 51.428136 -0.080766 -1.438711 0.865374 -0.002039 0.021637 0.979787 0.198858\n9778 51.435867 -0.080860 -1.438578 0.865356 -0.002642 0.022099 0.979756 0.198956\n9779 51.444776 -0.080781 -1.438711 0.865363 -0.002154 0.021752 0.979790 0.198833\n9780 51.452838 -0.080724 -1.438458 0.865426 -0.001517 0.021044 0.979786 0.198931\n9781 51.460705 -0.080695 -1.438465 0.865427 -0.001229 0.020847 0.979791 0.198930\n9782 51.471568 -0.080838 -1.438634 0.865348 -0.002527 0.022047 0.979757 0.198957\n9783 51.477379 -0.080427 -1.438510 0.865371 0.000009 0.020372 0.979786 0.199010\n9784 51.485068 -0.080650 -1.438489 0.865420 -0.000952 0.020654 0.979792 0.198947\n9785 51.493972 -0.080617 -1.438522 0.865417 -0.000760 0.020536 0.979787 0.198984\n9786 51.502805 -0.080769 -1.438726 0.865377 -0.001988 0.021682 0.979757 0.199003\n9787 51.512139 -0.080605 -1.438709 0.865210 -0.000594 0.019598 0.979686 0.199579\n9788 51.519887 -0.080623 -1.438512 0.865411 -0.000807 0.020542 0.979791 0.198967\n9789 51.527282 -0.080505 -1.438013 0.865604 -0.000983 0.020424 0.979559 0.200114\n9790 51.535553 -0.080679 -1.439210 0.865429 -0.001029 0.020710 0.979544 0.200161\n9791 51.546437 -0.080581 -1.438544 0.865404 -0.000595 0.020339 0.979787 0.199004\n9792 51.552699 -0.080539 -1.438995 0.865235 0.000581 0.020399 0.979804 0.198916\n9793 51.560245 -0.080801 -1.438638 0.865353 -0.002365 0.021871 0.979750 0.199015\n9794 51.569442 -0.080448 -1.438763 0.865363 -0.000023 0.019809 0.979748 0.199250\n9795 51.578074 -0.080612 -1.438899 0.865384 -0.001326 0.021025 0.979666 0.199525\n9796 51.585519 -0.080599 -1.438858 0.865390 -0.001343 0.020982 0.979654 0.199588\n9797 51.595215 -0.080813 -1.438659 0.865356 -0.002291 0.021896 0.979755 0.198985\n9798 51.603932 -0.080354 -1.438874 0.865177 0.000546 0.019727 0.979759 0.199204\n9799 51.611730 -0.080510 -1.438568 0.865382 -0.000275 0.020068 0.979785 0.199046\n9800 51.619412 -0.080809 -1.438407 0.865401 -0.002036 0.021592 0.979780 0.198900\n9801 51.627725 -0.080620 -1.438522 0.865407 -0.000803 0.020541 0.979789 0.198976\n9802 51.636175 -0.080689 -1.438525 0.865420 -0.001425 0.021029 0.979776 0.198986\n9803 51.644675 -0.080783 -1.438674 0.865356 -0.002224 0.021850 0.979753 0.199001\n9804 51.653790 -0.080460 -1.438345 0.865416 -0.000462 0.020232 0.979732 0.199286\n9805 51.660821 -0.080520 -1.438556 0.865389 -0.000368 0.020140 0.979782 0.199052\n9806 51.668608 -0.080746 -1.438443 0.865409 -0.001535 0.021084 0.979787 0.198925\n9807 51.677595 -0.080637 -1.438845 0.865377 -0.001406 0.021144 0.979689 0.199401\n9808 51.686220 -0.080575 -1.438499 0.865557 -0.000078 0.020301 0.979750 0.199192\n9809 51.694449 -0.080780 -1.438634 0.865354 -0.002257 0.021787 0.979742 0.199064\n9810 51.702390 -0.080779 -1.438678 0.865356 -0.002172 0.021775 0.979750 0.199027\n9811 51.711547 -0.080847 -1.438558 0.865340 -0.002722 0.022115 0.979750 0.198981\n9812 51.719171 -0.080771 -1.438431 0.865400 -0.001716 0.021238 0.979786 0.198911\n9813 51.728192 -0.080874 -1.438614 0.865337 -0.002627 0.022176 0.979760 0.198924\n9814 51.736249 -0.080778 -1.438639 0.865353 -0.002271 0.021851 0.979747 0.199031\n9815 51.744918 -0.080704 -1.438665 0.865364 -0.001897 0.021464 0.979734 0.199141\n9816 51.753243 -0.080856 -1.438671 0.865330 -0.002482 0.022159 0.979765 0.198906\n9817 51.760357 -0.080614 -1.439042 0.865238 0.000522 0.020671 0.979821 0.198806\n9818 51.770386 -0.080689 -1.439118 0.865402 -0.001136 0.020928 0.979584 0.199940\n9819 51.778280 -0.080890 -1.438539 0.865300 -0.003023 0.022400 0.979752 0.198938\n9820 51.786481 -0.080599 -1.438572 0.865400 -0.000910 0.020628 0.979770 0.199059\n9821 51.793330 -0.080271 -1.439012 0.865169 0.000780 0.019441 0.979690 0.199574\n9822 51.802476 -0.080656 -1.439047 0.865361 -0.001170 0.021087 0.979729 0.199213\n9823 51.811367 -0.080634 -1.438769 0.865357 -0.001518 0.021236 0.979706 0.199307\n9824 51.820117 -0.080681 -1.439275 0.865410 -0.000900 0.020292 0.979460 0.200615\n9825 51.828310 -0.080682 -1.438782 0.865347 -0.001736 0.021488 0.979770 0.198961\n9826 51.835656 -0.080889 -1.438526 0.865311 -0.002925 0.022300 0.979755 0.198935\n9827 51.846749 -0.080686 -1.438535 0.865410 -0.001367 0.021054 0.979770 0.199013\n9828 51.852622 -0.080859 -1.438547 0.865321 -0.002814 0.022165 0.979749 0.198981\n9829 51.860527 -0.080762 -1.438440 0.865403 -0.001562 0.021205 0.979787 0.198908\n9830 51.869765 -0.080831 -1.438607 0.865331 -0.002538 0.022011 0.979749 0.199002\n9831 51.877800 -0.080539 -1.438721 0.865379 -0.001152 0.020868 0.979617 0.199785\n9832 51.885433 -0.080717 -1.439178 0.865413 -0.000999 0.020473 0.979498 0.200409\n9833 51.894850 -0.080733 -1.438449 0.865397 -0.001373 0.021097 0.979787 0.198925\n9834 51.902462 -0.080731 -1.438450 0.865374 -0.001023 0.020788 0.979776 0.199014\n9835 51.911602 -0.080742 -1.438643 0.865352 -0.002076 0.021682 0.979740 0.199088\n9836 51.918855 -0.080866 -1.438552 0.865310 -0.002815 0.022264 0.979751 0.198957\n9837 51.928275 -0.080666 -1.438486 0.865403 -0.001165 0.020852 0.979800 0.198884\n9838 51.938113 -0.080407 -1.438698 0.865327 -0.000244 0.019687 0.979616 0.199911\n9839 51.944968 -0.080837 -1.438618 0.865326 -0.002504 0.022071 0.979749 0.198992\n9840 51.952241 -0.080826 -1.438666 0.865332 -0.002351 0.022020 0.979756 0.198967\n9841 51.960194 -0.080587 -1.437982 0.865634 -0.001295 0.020408 0.979462 0.200589\n9842 51.971073 -0.080805 -1.438561 0.865327 -0.002591 0.022005 0.979744 0.199023\n9843 51.978017 -0.080625 -1.438220 0.865197 -0.000815 0.021364 0.979727 0.199194\n9844 51.985734 -0.080698 -1.438477 0.865391 -0.001171 0.020925 0.979787 0.198944\n9845 51.994408 -0.080825 -1.438437 0.865363 -0.001939 0.021390 0.979755 0.199043\n9846 52.002935 -0.080584 -1.438541 0.865374 -0.000613 0.020399 0.979781 0.199030\n9847 52.011972 -0.080697 -1.439278 0.865400 -0.000918 0.020364 0.979475 0.200531\n9848 52.021142 -0.080543 -1.438623 0.865385 -0.000497 0.020388 0.979763 0.199120\n9849 52.027864 -0.080710 -1.439178 0.865394 -0.001090 0.020571 0.979504 0.200370\n9850 52.035805 -0.080874 -1.438562 0.865302 -0.002760 0.022255 0.979757 0.198933\n9851 52.044728 -0.080519 -1.438383 0.865243 -0.000740 0.021101 0.979643 0.199637\n9852 52.052659 -0.080617 -1.438830 0.865355 -0.001365 0.021179 0.979684 0.199422\n9853 52.061481 -0.080895 -1.438531 0.865289 -0.002959 0.022441 0.979753 0.198928\n9854 52.070074 -0.080888 -1.438536 0.865298 -0.002842 0.022318 0.979752 0.198949\n9855 52.078214 -0.080767 -1.438608 0.865331 -0.002264 0.021820 0.979744 0.199048\n9856 52.085319 -0.080853 -1.438510 0.865313 -0.002797 0.022180 0.979743 0.199005\n9857 52.094835 -0.080712 -1.438424 0.865382 -0.001563 0.021275 0.979773 0.198974\n9858 52.102848 -0.080700 -1.438625 0.865348 -0.001911 0.021553 0.979727 0.199164\n9859 52.111452 -0.080530 -1.438567 0.865362 -0.000331 0.020170 0.979782 0.199046\n9860 52.119383 -0.080870 -1.438529 0.865293 -0.002878 0.022277 0.979750 0.198960\n9861 52.128042 -0.080778 -1.438610 0.865328 -0.002282 0.021861 0.979741 0.199059\n9862 52.136297 -0.080847 -1.438620 0.865311 -0.002539 0.022172 0.979753 0.198961\n9863 52.145022 -0.080823 -1.438565 0.865314 -0.002597 0.022105 0.979741 0.199027\n9864 52.154009 -0.080596 -1.438910 0.865385 -0.001097 0.020702 0.979575 0.200007\n9865 52.161824 -0.080672 -1.438663 0.865345 -0.001768 0.021445 0.979722 0.199205\n9866 52.170117 -0.080889 -1.438527 0.865275 -0.003021 0.022429 0.979747 0.198956\n9867 52.178080 -0.080834 -1.438529 0.865308 -0.002692 0.022092 0.979742 0.199022\n9868 52.186103 -0.080343 -1.438543 0.865326 -0.000573 0.019289 0.979518 0.200430\n9869 52.194601 -0.080790 -1.438467 0.865360 -0.001740 0.021256 0.979759 0.199043\n9870 52.202224 -0.080765 -1.438591 0.865327 -0.002226 0.021803 0.979741 0.199067\n9871 52.211689 -0.080397 -1.438808 0.865261 0.000808 0.020798 0.979870 0.198549\n9872 52.219844 -0.080677 -1.439183 0.865389 -0.001013 0.020538 0.979497 0.200407\n9873 52.228271 -0.080784 -1.438581 0.865325 -0.002368 0.021882 0.979742 0.199050\n9874 52.235904 -0.080735 -1.438627 0.865332 -0.002088 0.021675 0.979737 0.199101\n9875 52.244302 -0.080596 -1.438645 0.865386 -0.001009 0.020824 0.979751 0.199131\n9876 52.253873 -0.080730 -1.439157 0.865372 -0.001049 0.020643 0.979525 0.200260\n9877 52.260956 -0.080717 -1.438646 0.865331 -0.002015 0.021648 0.979732 0.199129\n9878 52.270144 -0.080730 -1.438686 0.865345 -0.001871 0.021607 0.979734 0.199123\n9879 52.278128 -0.080699 -1.439214 0.865388 -0.001027 0.020564 0.979494 0.200418\n9880 52.286178 -0.080813 -1.438417 0.865362 -0.001980 0.021593 0.979776 0.198918\n9881 52.293400 -0.080758 -1.438982 0.865233 -0.000179 0.020613 0.979656 0.199625\n9882 52.302244 -0.080692 -1.438649 0.865334 -0.001834 0.021512 0.979728 0.199167\n9883 52.311093 -0.080724 -1.438470 0.865380 -0.001290 0.021005 0.979782 0.198956\n9884 52.318874 -0.080476 -1.439053 0.865408 -0.000575 0.020249 0.979563 0.200116\n9885 52.328171 -0.080611 -1.438674 0.865386 -0.001052 0.020796 0.979727 0.199254\n9886 52.336775 -0.080472 -1.438966 0.865180 0.001197 0.021181 0.979968 0.198021\n9887 52.345584 -0.080808 -1.438409 0.865362 -0.001967 0.021569 0.979776 0.198920\n9888 52.353027 -0.080603 -1.438650 0.865366 -0.001025 0.020830 0.979744 0.199163\n9889 52.361529 -0.080692 -1.438763 0.865335 -0.001565 0.021454 0.979719 0.199217\n9890 52.370333 -0.080723 -1.438497 0.865371 -0.001565 0.021225 0.979774 0.198974\n9891 52.378142 -0.080703 -1.439289 0.865376 -0.000883 0.020442 0.979466 0.200571\n9892 52.385272 -0.080788 -1.438439 0.865358 -0.001777 0.021475 0.979777 0.198928\n9893 52.394358 -0.080471 -1.438629 0.865360 -0.000543 0.020284 0.979721 0.199337\n9894 52.403468 -0.080705 -1.438521 0.865373 -0.001450 0.021163 0.979768 0.199008\n9895 52.411451 -0.080809 -1.438430 0.865359 -0.001911 0.021582 0.979775 0.198927\n9896 52.419032 -0.080789 -1.438414 0.865341 -0.002011 0.021748 0.979765 0.198955\n9897 52.428871 -0.080523 -1.438598 0.865338 -0.000212 0.020201 0.979780 0.199056\n9898 52.436463 -0.080670 -1.439193 0.865376 -0.000945 0.020535 0.979488 0.200449\n9899 52.444078 -0.080818 -1.438669 0.865302 -0.002275 0.022083 0.979748 0.199002\n9900 52.452575 -0.080760 -1.438448 0.865368 -0.001522 0.021249 0.979780 0.198940\n9901 52.461069 -0.080615 -1.438138 0.865178 -0.000737 0.021583 0.979812 0.198753\n9902 52.468855 -0.080638 -1.438438 0.865353 -0.000705 0.020759 0.979757 0.199111\n9903 52.478090 -0.080645 -1.438663 0.865329 -0.001699 0.021404 0.979718 0.199228\n9904 52.485901 -0.080678 -1.439226 0.865375 -0.000921 0.020487 0.979479 0.200500\n9905 52.494783 -0.080759 -1.438592 0.865317 -0.002236 0.021851 0.979735 0.199091\n9906 52.503265 -0.080673 -1.438687 0.865330 -0.001724 0.021499 0.979722 0.199199\n9907 52.510314 -0.080834 -1.438551 0.865288 -0.002657 0.022242 0.979742 0.199008\n9908 52.519037 -0.080707 -1.438480 0.865366 -0.001121 0.020926 0.979783 0.198963\n9909 52.527678 -0.080737 -1.438630 0.865318 -0.002005 0.021738 0.979730 0.199130\n9910 52.536852 -0.080745 -1.438667 0.865314 -0.001991 0.021732 0.979728 0.199138\n9911 52.545278 -0.080489 -1.438454 0.865328 -0.000158 0.020110 0.979794 0.198997\n9912 52.552776 -0.080854 -1.438537 0.865276 -0.002738 0.022282 0.979742 0.198999\n9913 52.561283 -0.080677 -1.439160 0.865367 -0.000923 0.020546 0.979499 0.200395\n9914 52.568894 -0.080829 -1.438596 0.865286 -0.002472 0.022174 0.979745 0.199004\n9915 52.577859 -0.080685 -1.439175 0.865366 -0.000952 0.020610 0.979493 0.200418\n9916 52.586849 -0.080885 -1.438534 0.865262 -0.002876 0.022468 0.979746 0.198961\n9917 52.594878 -0.080464 -1.438774 0.865335 -0.000273 0.020276 0.979723 0.199328\n9918 52.602388 -0.080719 -1.439258 0.865382 -0.001006 0.020955 0.979530 0.200203\n9919 52.611412 -0.080815 -1.438565 0.865295 -0.002502 0.022050 0.979741 0.199035\n9920 52.619497 -0.080792 -1.438629 0.865300 -0.002251 0.021959 0.979742 0.199046\n9921 52.626839 -0.080714 -1.439265 0.865381 -0.000880 0.020856 0.979529 0.200220\n9922 52.635541 -0.080613 -1.438727 0.865321 -0.001438 0.021274 0.979692 0.199370\n9923 52.645472 -0.080804 -1.438575 0.865292 -0.002416 0.022077 0.979737 0.199054\n9924 52.653686 -0.080683 -1.439194 0.865377 -0.001051 0.020850 0.979505 0.200335\n9925 52.661380 -0.080671 -1.438808 0.865316 -0.001426 0.021452 0.979713 0.199248\n9926 52.668937 -0.080816 -1.438414 0.865334 -0.001951 0.021668 0.979773 0.198925\n9927 52.677646 -0.080710 -1.439278 0.865348 -0.000939 0.020532 0.979490 0.200440\n9928 52.686762 -0.080666 -1.438819 0.865319 -0.001359 0.021363 0.979703 0.199309\n9929 52.695508 -0.080778 -1.438437 0.865343 -0.001832 0.021514 0.979774 0.198939\n9930 52.702742 -0.080717 -1.438651 0.865313 -0.001924 0.021688 0.979729 0.199140\n9931 52.711335 -0.080514 -1.438950 0.865218 0.000354 0.020523 0.979764 0.199102\n9932 52.718913 -0.080709 -1.438663 0.865312 -0.001820 0.021633 0.979726 0.199163\n9933 52.728344 -0.080688 -1.439240 0.865359 -0.000897 0.020498 0.979483 0.200478\n9934 52.736608 -0.080824 -1.438589 0.865279 -0.002520 0.022176 0.979743 0.199012\n9935 52.744782 -0.080793 -1.438431 0.865348 -0.001714 0.021475 0.979776 0.198934\n9936 52.752069 -0.080810 -1.438572 0.865278 -0.002518 0.022161 0.979742 0.199018\n9937 52.763016 -0.080672 -1.438689 0.865309 -0.001623 0.021530 0.979720 0.199206\n9938 52.769278 -0.080623 -1.438539 0.865344 -0.000672 0.020651 0.979783 0.198996\n9939 52.776794 -0.080693 -1.438664 0.865305 -0.001807 0.021643 0.979722 0.199182\n9940 52.785623 -0.080544 -1.438779 0.865337 -0.001068 0.020969 0.979583 0.199940\n9941 52.794599 -0.080586 -1.438543 0.865500 -0.000031 0.020424 0.979722 0.199321\n9942 52.803520 -0.080695 -1.439255 0.865344 -0.000857 0.020523 0.979483 0.200476\n9943 52.811378 -0.080713 -1.439244 0.865336 -0.000931 0.020582 0.979498 0.200398\n9944 52.818945 -0.080749 -1.438421 0.865314 -0.002013 0.021707 0.979759 0.198993\n9945 52.828817 -0.080679 -1.439219 0.865347 -0.000893 0.020591 0.979492 0.200424\n9946 52.837583 -0.080863 -1.438520 0.865248 -0.002849 0.022435 0.979744 0.198974\n9947 52.844205 -0.080812 -1.438616 0.865269 -0.002440 0.022139 0.979740 0.199030\n9948 52.852003 -0.080810 -1.438563 0.865277 -0.002443 0.022073 0.979738 0.199049\n9949 52.861767 -0.080476 -1.438465 0.865305 -0.000105 0.020107 0.979790 0.199014\n9950 52.870151 -0.080672 -1.438504 0.865340 -0.000968 0.020845 0.979783 0.198973\n9951 52.879410 -0.080683 -1.439233 0.865352 -0.000918 0.020591 0.979493 0.200420\n9952 52.886063 -0.080769 -1.438384 0.865329 -0.001514 0.021294 0.979784 0.198918\n9953 52.893504 -0.080872 -1.438503 0.865239 -0.002970 0.022469 0.979742 0.198975\n9954 52.902052 -0.080830 -1.438551 0.865274 -0.002611 0.022240 0.979742 0.199010\n9955 52.911081 -0.080698 -1.439215 0.865348 -0.000960 0.020683 0.979495 0.200402\n9956 52.920597 -0.080641 -1.438647 0.865311 -0.001633 0.021455 0.979713 0.199246\n9957 52.927947 -0.080809 -1.438573 0.865282 -0.002419 0.022081 0.979741 0.199034\n9958 52.936634 -0.080590 -1.438773 0.865311 -0.001311 0.021177 0.979677 0.199457\n9959 52.944835 -0.080515 -1.438575 0.865311 -0.000200 0.020193 0.979779 0.199061\n9960 52.953883 -0.080617 -1.438656 0.865357 -0.001043 0.020934 0.979734 0.199203\n9961 52.961251 -0.080872 -1.438513 0.865249 -0.002891 0.022413 0.979739 0.198997\n9962 52.969300 -0.080708 -1.438616 0.865298 -0.001933 0.021705 0.979728 0.199143\n9963 52.978983 -0.080510 -1.438484 0.865301 -0.000143 0.020203 0.979789 0.199013\n9964 52.987591 -0.080693 -1.438538 0.865342 -0.001382 0.021187 0.979766 0.199019\n9965 52.994796 -0.080439 -1.438792 0.865287 0.000085 0.020007 0.979732 0.199310\n9966 53.001936 -0.080846 -1.438545 0.865253 -0.002719 0.022334 0.979741 0.198999\n9967 53.010828 -0.080840 -1.438547 0.865261 -0.002638 0.022282 0.979741 0.199010\n9968 53.020245 -0.080777 -1.438609 0.865279 -0.002224 0.022052 0.979738 0.199055\n9969 53.028394 -0.080801 -1.438427 0.865322 -0.001831 0.021604 0.979772 0.198937\n9970 53.035892 -0.080755 -1.438586 0.865283 -0.002166 0.021908 0.979735 0.199086\n9971 53.048398 -0.080822 -1.438536 0.865264 -0.002593 0.022227 0.979737 0.199036\n9972 53.053892 -0.080569 -1.438751 0.865310 -0.001293 0.021208 0.979665 0.199514\n9973 53.061547 -0.080288 -1.438989 0.865326 -0.000166 0.019753 0.979544 0.200256\n9974 53.069119 -0.080843 -1.438553 0.865252 -0.002717 0.022323 0.979739 0.199013\n9975 53.077734 -0.080676 -1.438744 0.865297 -0.001533 0.021488 0.979712 0.199250\n9976 53.085679 -0.080721 -1.438645 0.865293 -0.001919 0.021789 0.979725 0.199148\n9977 53.096562 -0.080563 -1.438566 0.865314 -0.000410 0.020498 0.979778 0.199035\n9978 53.102895 -0.080835 -1.438607 0.865262 -0.002510 0.022310 0.979741 0.199007\n9979 53.111439 -0.080837 -1.438600 0.865257 -0.002444 0.022322 0.979747 0.198976\n9980 53.118967 -0.080443 -1.438854 0.865318 -0.000258 0.020393 0.979697 0.199446\n9981 53.127495 -0.080656 -1.439176 0.865343 -0.000895 0.020618 0.979488 0.200444\n9982 53.135647 -0.080879 -1.438551 0.865242 -0.002744 0.022497 0.979745 0.198961\n9983 53.145219 -0.080732 -1.438473 0.865330 -0.001431 0.021254 0.979775 0.198967\n9984 53.153197 -0.080708 -1.438497 0.865333 -0.001330 0.021201 0.979775 0.198973\n9985 53.161379 -0.080661 -1.438590 0.865337 -0.001186 0.021118 0.979752 0.199094\n9986 53.168609 -0.080400 -1.438825 0.865276 0.000132 0.019976 0.979720 0.199374\n9987 53.177386 -0.080714 -1.438485 0.865336 -0.001088 0.021037 0.979781 0.198959\n9988 53.186742 -0.080623 -1.438545 0.865330 -0.000811 0.020858 0.979774 0.199017\n9989 53.194982 -0.080701 -1.438586 0.865287 -0.001910 0.021692 0.979726 0.199153\n9990 53.202146 -0.080801 -1.438582 0.865261 -0.002381 0.022149 0.979740 0.199031\n9991 53.211557 -0.080881 -1.438550 0.865229 -0.002838 0.022595 0.979743 0.198962\n9992 53.219928 -0.080870 -1.438502 0.865222 -0.002968 0.022587 0.979739 0.198976\n9993 53.226936 -0.080591 -1.438529 0.865484 -0.000135 0.020465 0.979677 0.199534\n9994 53.235868 -0.080531 -1.438578 0.865288 -0.000285 0.020358 0.979775 0.199064\n9995 53.244466 -0.080775 -1.438590 0.865261 -0.002226 0.022040 0.979737 0.199059\n9996 53.252155 -0.080669 -1.438496 0.865314 -0.000955 0.020939 0.979778 0.198985\n9997 53.262096 -0.080674 -1.439114 0.865321 -0.001053 0.021113 0.979549 0.200092\n9998 53.269543 -0.080568 -1.438720 0.865334 -0.000874 0.020843 0.979700 0.199382\n9999 53.278121 -0.080734 -1.438646 0.865264 -0.001968 0.021830 0.979733 0.199103\n10000 53.285658 -0.080392 -1.438942 0.865245 0.000291 0.019751 0.979710 0.199443\n10001 53.293946 -0.080684 -1.439181 0.865326 -0.000972 0.020745 0.979503 0.200357\n10002 53.303404 -0.080816 -1.438602 0.865254 -0.002365 0.022191 0.979737 0.199042\n10003 53.312292 -0.080669 -1.439240 0.865329 -0.000805 0.020600 0.979479 0.200491\n10004 53.319942 -0.080576 -1.438596 0.865323 -0.000635 0.020741 0.979761 0.199093\n10005 53.328069 -0.080668 -1.438505 0.865322 -0.000932 0.020935 0.979781 0.198974\n10006 53.335115 -0.080679 -1.439252 0.865331 -0.000825 0.020575 0.979480 0.200486\n10007 53.344173 -0.080684 -1.439177 0.865326 -0.000944 0.020778 0.979505 0.200345\n10008 53.351860 -0.080314 -1.438526 0.865362 0.000208 0.020380 0.979693 0.199467\n10009 53.360035 -0.080784 -1.438432 0.865309 -0.001661 0.021555 0.979774 0.198935\n10010 53.370147 -0.080698 -1.439198 0.865336 -0.000995 0.021077 0.979523 0.200224\n10011 53.377429 -0.080685 -1.438674 0.865279 -0.001689 0.021682 0.979719 0.199192\n10012 53.386116 -0.080540 -1.438598 0.865292 -0.001212 0.021243 0.979667 0.199498\n10013 53.395215 -0.080589 -1.438835 0.865302 -0.001153 0.021221 0.979630 0.199683\n10014 53.402386 -0.080677 -1.438696 0.865278 -0.001607 0.021624 0.979715 0.199219\n10015 53.411563 -0.080821 -1.438528 0.865252 -0.002457 0.022228 0.979737 0.199039\n10016 53.419986 -0.080765 -1.438450 0.865313 -0.001482 0.021419 0.979776 0.198942\n10017 53.429584 -0.080829 -1.438587 0.865243 -0.002447 0.022292 0.979740 0.199013\n10018 53.435903 -0.080635 -1.438528 0.865307 -0.000645 0.020803 0.979783 0.198980\n10019 53.443417 -0.080677 -1.438547 0.865320 -0.001191 0.021201 0.979765 0.199023\n10020 53.454785 -0.080572 -1.438565 0.865294 -0.000419 0.020545 0.979776 0.199039\n10021 53.460964 -0.080865 -1.438519 0.865221 -0.002814 0.022530 0.979739 0.198986\n10022 53.469355 -0.080875 -1.438553 0.865218 -0.002772 0.022573 0.979743 0.198962\n10023 53.478073 -0.080871 -1.438487 0.865217 -0.002890 0.022500 0.979738 0.198993\n10024 53.486926 -0.080783 -1.438443 0.865305 -0.001639 0.021448 0.979772 0.198956\n10025 53.493319 -0.080594 -1.438660 0.865279 -0.001421 0.021398 0.979696 0.199339\n10026 53.504619 -0.080831 -1.438554 0.865242 -0.002528 0.022301 0.979739 0.199019\n10027 53.511612 -0.080560 -1.438589 0.865293 -0.000297 0.020477 0.979777 0.199040\n10028 53.520048 -0.080824 -1.438414 0.865295 -0.001967 0.021764 0.979769 0.198937\n10029 53.527774 -0.080614 -1.438748 0.865274 -0.001340 0.021438 0.979701 0.199308\n10030 53.535019 -0.080885 -1.438526 0.865209 -0.002897 0.022653 0.979738 0.198979\n10031 53.546287 -0.080751 -1.438628 0.865261 -0.002013 0.021991 0.979732 0.199094\n10032 53.552220 -0.080757 -1.438627 0.865261 -0.002009 0.021941 0.979730 0.199107\n10033 53.561386 -0.080680 -1.439210 0.865322 -0.000851 0.020748 0.979490 0.200418\n10034 53.568667 -0.080755 -1.438416 0.865276 -0.001951 0.021805 0.979755 0.198998\n10035 53.578610 -0.080534 -1.438705 0.865292 -0.001090 0.021143 0.979616 0.199763\n10036 53.588218 -0.080742 -1.438463 0.865312 -0.001296 0.021331 0.979776 0.198955\n10037 53.594949 -0.080588 -1.438925 0.865317 -0.000951 0.020904 0.979568 0.200023\n10038 53.603795 -0.080867 -1.438520 0.865219 -0.002803 0.022568 0.979740 0.198981\n10039 53.611441 -0.080859 -1.438517 0.865215 -0.002768 0.022500 0.979739 0.198989\n10040 53.618359 -0.080710 -1.439279 0.865333 -0.000862 0.021069 0.979498 0.200349\n10041 53.627534 -0.080562 -1.438541 0.865283 -0.001285 0.021371 0.979691 0.199367\n10042 53.636715 -0.080781 -1.438438 0.865304 -0.001669 0.021609 0.979770 0.198951\n10043 53.644334 -0.080759 -1.438456 0.865303 -0.001403 0.021373 0.979777 0.198945\n10044 53.651755 -0.080804 -1.438424 0.865292 -0.001828 0.021749 0.979770 0.198934\n10045 53.661550 -0.080628 -1.438635 0.865272 -0.001524 0.021521 0.979703 0.199290\n10046 53.670627 -0.080869 -1.438500 0.865205 -0.002872 0.022591 0.979740 0.198975\n10047 53.677872 -0.080756 -1.438465 0.865300 -0.001526 0.021508 0.979772 0.198954\n10048 53.686847 -0.080673 -1.438610 0.865269 -0.001757 0.021724 0.979717 0.199196\n10049 53.694108 -0.080681 -1.439231 0.865303 -0.000853 0.020719 0.979489 0.200426\n10050 53.702170 -0.080704 -1.438601 0.865262 -0.001859 0.021795 0.979724 0.199154\n10051 53.711272 -0.080793 -1.438570 0.865242 -0.002337 0.022213 0.979733 0.199060\n10052 53.720763 -0.080482 -1.438455 0.865270 -0.000006 0.020269 0.979783 0.199033\n10053 53.727958 -0.080846 -1.438574 0.865218 -0.002564 0.022465 0.979741 0.198989\n10054 53.736956 -0.080531 -1.438539 0.865287 -0.001306 0.021285 0.979682 0.199419\n10055 53.743721 -0.080710 -1.438487 0.865305 -0.001095 0.021220 0.979778 0.198958\n10056 53.756107 -0.080852 -1.438543 0.865226 -0.002598 0.022454 0.979740 0.198994\n10057 53.761385 -0.080574 -1.438569 0.865472 0.000066 0.020530 0.979700 0.199416\n10058 53.769730 -0.080669 -1.438639 0.865270 -0.001616 0.021689 0.979711 0.199232\n10059 53.778121 -0.080581 -1.438678 0.865308 -0.000842 0.020998 0.979739 0.199175\n10060 53.786498 -0.080795 -1.438576 0.865244 -0.002283 0.022215 0.979732 0.199067\n10061 53.794639 -0.080627 -1.438390 0.865275 -0.000601 0.020898 0.979791 0.198928\n10062 53.802210 -0.080704 -1.439296 0.865314 -0.000775 0.020695 0.979479 0.200480\n10063 53.811332 -0.080767 -1.438454 0.865306 -0.001426 0.021489 0.979775 0.198939\n10064 53.820545 -0.080690 -1.439203 0.865320 -0.000906 0.021154 0.979542 0.200125\n10065 53.827698 -0.080871 -1.438538 0.865214 -0.002735 0.022573 0.979736 0.198999\n10066 53.835392 -0.080603 -1.438949 0.865308 -0.000956 0.020921 0.979567 0.200023\n10067 53.844769 -0.080624 -1.438731 0.865269 -0.001343 0.021483 0.979697 0.199323\n10068 53.852886 -0.080694 -1.438717 0.865263 -0.001598 0.021771 0.979725 0.199155\n10069 53.862110 -0.080428 -1.438746 0.865242 0.000196 0.019986 0.979746 0.199243\n10070 53.869169 -0.080709 -1.438498 0.865300 -0.001302 0.021329 0.979770 0.198984\n10071 53.876806 -0.080757 -1.438603 0.865256 -0.002078 0.022021 0.979730 0.199096\n10072 53.885341 -0.080826 -1.438536 0.865229 -0.002550 0.022373 0.979736 0.199025\n10073 53.894300 -0.080765 -1.438376 0.865274 -0.001823 0.021788 0.979767 0.198945\n10074 53.903419 -0.080701 -1.438635 0.865268 -0.001718 0.021804 0.979725 0.199150\n10075 53.912379 -0.080654 -1.438646 0.865266 -0.001591 0.021627 0.979710 0.199244\n10076 53.919654 -0.080647 -1.438530 0.865299 -0.000679 0.020888 0.979775 0.199009\n10077 53.928918 -0.080764 -1.438467 0.865294 -0.001588 0.021629 0.979770 0.198949\n10078 53.936571 -0.080413 -1.438671 0.865335 0.001398 0.021598 0.980100 0.197323\n10079 53.943398 -0.080472 -1.439134 0.865314 -0.000204 0.020603 0.979605 0.199872\n10080 53.951928 -0.080625 -1.438727 0.865266 -0.001338 0.021501 0.979689 0.199364\n10081 53.960917 -0.080667 -1.439192 0.865316 -0.000803 0.020808 0.979501 0.200359\n10082 53.970167 -0.080879 -1.438524 0.865203 -0.002763 0.022601 0.979738 0.198985\n10083 53.978280 -0.080825 -1.438540 0.865218 -0.002550 0.022416 0.979735 0.199023\n10084 53.985710 -0.080630 -1.438647 0.865314 -0.000951 0.021105 0.979734 0.199188\n10085 53.993270 -0.080804 -1.438466 0.865278 -0.001653 0.021638 0.979746 0.199067\n10086 54.004656 -0.080769 -1.438464 0.865288 -0.001592 0.021635 0.979766 0.198966\n10087 54.010862 -0.080833 -1.438525 0.865225 -0.002573 0.022389 0.979733 0.199038\n10088 54.020064 -0.080663 -1.439178 0.865308 -0.000851 0.020866 0.979502 0.200351\n10089 54.028167 -0.080772 -1.438469 0.865289 -0.001685 0.021683 0.979765 0.198967\n10090 54.035182 -0.080695 -1.438490 0.865298 -0.000979 0.021220 0.979777 0.198962\n10091 54.044558 -0.080809 -1.438370 0.865265 -0.001935 0.021817 0.979768 0.198937\n10092 54.053317 -0.080797 -1.438434 0.865276 -0.001776 0.021773 0.979769 0.198937\n10093 54.062150 -0.080400 -1.438964 0.865096 0.001248 0.021211 0.979959 0.198063\n10094 54.070905 -0.080574 -1.438810 0.865263 -0.001126 0.021339 0.979651 0.199566\n10095 54.078153 -0.080555 -1.438575 0.865271 -0.000281 0.020596 0.979771 0.199059\n10096 54.087194 -0.080663 -1.439285 0.865296 -0.000750 0.020674 0.979467 0.200541\n10097 54.094846 -0.080735 -1.438575 0.865235 -0.002141 0.022040 0.979726 0.199113\n10098 54.102883 -0.080607 -1.438691 0.865253 -0.001367 0.021492 0.979696 0.199329\n10099 54.111026 -0.080764 -1.438559 0.865226 -0.002204 0.022107 0.979731 0.199084\n10100 54.118335 -0.080737 -1.438625 0.865239 -0.001959 0.021959 0.979728 0.199116\n10101 54.128505 -0.080631 -1.438695 0.865249 -0.001399 0.021540 0.979704 0.199283\n10102 54.136856 -0.080863 -1.438495 0.865192 -0.002777 0.022605 0.979734 0.199004\n10103 54.144696 -0.080772 -1.438559 0.865228 -0.002254 0.022198 0.979729 0.199084\n10104 54.151499 -0.080728 -1.438605 0.865245 -0.001897 0.021924 0.979727 0.199125\n10105 54.161340 -0.080610 -1.439022 0.865278 -0.000977 0.021228 0.979581 0.199923\n10106 54.169981 -0.080594 -1.438917 0.865289 -0.000938 0.020987 0.979580 0.199954\n10107 54.177754 -0.080773 -1.438586 0.865225 -0.002252 0.022234 0.979731 0.199068\n10108 54.185017 -0.080698 -1.438512 0.865289 -0.001191 0.021321 0.979769 0.198989\n10109 54.193324 -0.080750 -1.438467 0.865282 -0.001563 0.021646 0.979768 0.198956\n10110 54.203735 -0.080823 -1.438476 0.865257 -0.001678 0.021624 0.979729 0.199148\n10111 54.211022 -0.080674 -1.438510 0.865289 -0.000867 0.021119 0.979775 0.198983\n10112 54.219910 -0.080523 -1.438593 0.865257 -0.000170 0.020468 0.979771 0.199074\n10113 54.228014 -0.080646 -1.439241 0.865301 -0.000701 0.020702 0.979470 0.200523\n10114 54.235678 -0.080394 -1.438817 0.865236 0.000187 0.020166 0.979718 0.199364\n10115 54.245460 -0.080830 -1.438556 0.865208 -0.002491 0.022451 0.979736 0.199016\n10116 54.252736 -0.080539 -1.438573 0.865254 -0.000269 0.020566 0.979771 0.199061\n10117 54.261313 -0.080788 -1.438565 0.865222 -0.002287 0.022256 0.979730 0.199070\n10118 54.268393 -0.080775 -1.438601 0.865215 -0.002238 0.022247 0.979728 0.199079\n10119 54.277602 -0.080805 -1.438436 0.865267 -0.001804 0.021852 0.979764 0.198954\n10120 54.285470 -0.080747 -1.438480 0.865278 -0.001546 0.021631 0.979765 0.198975\n10121 54.294609 -0.080849 -1.438539 0.865184 -0.002696 0.022635 0.979733 0.199006\n10122 54.304000 -0.080665 -1.439513 0.864717 0.001124 0.020830 0.979892 0.198438\n10123 54.311199 -0.080586 -1.438919 0.865282 -0.000914 0.021024 0.979578 0.199960\n10124 54.319584 -0.080757 -1.438456 0.865272 -0.001581 0.021656 0.979765 0.198968\n10125 54.326630 -0.080652 -1.438551 0.865272 -0.000780 0.020955 0.979756 0.199096\n10126 54.337922 -0.080639 -1.438525 0.865272 -0.000615 0.020954 0.979776 0.198997\n10127 54.343605 -0.080861 -1.438513 0.865184 -0.002828 0.022719 0.979730 0.199009\n10128 54.353300 -0.080866 -1.438518 0.865187 -0.002739 0.022717 0.979733 0.198995\n10129 54.361500 -0.080574 -1.438908 0.865261 -0.000995 0.021257 0.979601 0.199820\n10130 54.369948 -0.080809 -1.438556 0.865210 -0.002361 0.022339 0.979729 0.199064\n10131 54.377690 -0.080829 -1.438523 0.865195 -0.002582 0.022514 0.979732 0.199026\n10132 54.384938 -0.080351 -1.438225 0.865551 -0.000460 0.020558 0.979524 0.200273\n10133 54.394256 -0.080746 -1.438591 0.865226 -0.001973 0.022083 0.979722 0.199131\n10134 54.402314 -0.080611 -1.438554 0.865267 -0.000505 0.020805 0.979773 0.199028\n10135 54.412161 -0.080625 -1.438691 0.865242 -0.001385 0.021650 0.979700 0.199294\n10136 54.420052 -0.080669 -1.438518 0.865271 -0.000749 0.021070 0.979775 0.198988\n10137 54.427825 -0.080636 -1.438654 0.865235 -0.001493 0.021660 0.979709 0.199247\n10138 54.435747 -0.080795 -1.438475 0.865248 -0.001672 0.021661 0.979740 0.199093\n10139 54.443548 -0.080597 -1.438887 0.865269 -0.000957 0.021070 0.979591 0.199892\n10140 54.451581 -0.080455 -1.438443 0.865235 0.000079 0.020361 0.979788 0.198998\n10141 54.460113 -0.080743 -1.438587 0.865229 -0.002007 0.022111 0.979725 0.199113\n10142 54.469772 -0.080854 -1.438531 0.865174 -0.002757 0.022727 0.979732 0.199003\n10143 54.477921 -0.080647 -1.439150 0.865277 -0.000775 0.020871 0.979510 0.200309\n10144 54.486350 -0.080555 -1.438357 0.865135 -0.000735 0.021655 0.979632 0.199631\n10145 54.494231 -0.080657 -1.438764 0.865233 -0.001333 0.021658 0.979706 0.199261\n10146 54.501784 -0.080753 -1.438420 0.865242 -0.001865 0.021930 0.979750 0.199013\n10147 54.512120 -0.080735 -1.438443 0.865240 -0.001787 0.021886 0.979747 0.199030\n10148 54.520205 -0.080686 -1.438545 0.865270 -0.001257 0.021435 0.979757 0.199034\n10149 54.527772 -0.080785 -1.438595 0.865207 -0.002232 0.022268 0.979728 0.199080\n10150 54.536661 -0.080640 -1.438619 0.865278 -0.001017 0.021270 0.979735 0.199161\n10151 54.544213 -0.080733 -1.438603 0.865219 -0.002004 0.022087 0.979723 0.199125\n10152 54.552193 -0.080532 -1.438836 0.865328 -0.000057 0.020450 0.979560 0.200110\n10153 54.561270 -0.080789 -1.438605 0.865206 -0.002180 0.022281 0.979732 0.199059\n10154 54.571182 -0.080754 -1.438461 0.865263 -0.001391 0.021622 0.979769 0.198958\n10155 54.577876 -0.080749 -1.438462 0.865268 -0.001402 0.021569 0.979769 0.198964\n10156 54.586320 -0.080344 -1.438581 0.865318 0.000217 0.020562 0.979657 0.199622\n10157 54.593758 -0.080787 -1.438600 0.865203 -0.002208 0.022308 0.979728 0.199076\n10158 54.604027 -0.080571 -1.438573 0.865255 -0.000327 0.020777 0.979770 0.199044\n10159 54.611621 -0.080667 -1.438510 0.865264 -0.000867 0.021187 0.979773 0.198987\n10160 54.620073 -0.080852 -1.438546 0.865176 -0.002623 0.022639 0.979736 0.198990\n10161 54.628000 -0.080705 -1.438612 0.865223 -0.001791 0.022000 0.979718 0.199161\n10162 54.635016 -0.080690 -1.439320 0.865288 -0.000772 0.021197 0.979508 0.200286\n10163 54.643392 -0.080733 -1.438473 0.865267 -0.001242 0.021435 0.979770 0.198970\n10164 54.654135 -0.080853 -1.438541 0.865165 -0.002778 0.022740 0.979732 0.198998\n10165 54.661509 -0.080803 -1.438487 0.865242 -0.001624 0.021638 0.979733 0.199130\n10166 54.670432 -0.080748 -1.438469 0.865259 -0.001419 0.021627 0.979769 0.198952\n10167 54.677700 -0.080868 -1.438529 0.865167 -0.002784 0.022750 0.979734 0.198990\n10168 54.685597 -0.080790 -1.438566 0.865200 -0.002282 0.022356 0.979730 0.199057\n10169 54.695483 -0.080595 -1.438972 0.865263 -0.000972 0.021273 0.979571 0.199968\n10170 54.703177 -0.080461 -1.438449 0.865220 0.000073 0.020377 0.979782 0.199028\n10171 54.711088 -0.080819 -1.438572 0.865191 -0.002427 0.022471 0.979728 0.199051\n10172 54.719653 -0.080653 -1.439189 0.865286 -0.000843 0.021221 0.979505 0.200296\n10173 54.726932 -0.080669 -1.439258 0.865261 -0.000734 0.020805 0.979484 0.200442\n10174 54.736664 -0.080740 -1.438609 0.865214 -0.001932 0.022114 0.979723 0.199126\n10175 54.744896 -0.080845 -1.438507 0.865162 -0.002816 0.022707 0.979728 0.199022\n10176 54.752025 -0.080843 -1.438596 0.865181 -0.002378 0.022624 0.979740 0.198979\n10177 54.759945 -0.080850 -1.438547 0.865173 -0.002657 0.022695 0.979733 0.199003\n10178 54.770618 -0.080736 -1.438659 0.865207 -0.001868 0.022144 0.979727 0.199103\n10179 54.777373 -0.080627 -1.438539 0.865250 -0.000536 0.021014 0.979772 0.199009\n10180 54.786631 -0.080771 -1.438581 0.865206 -0.002152 0.022291 0.979725 0.199092\n10181 54.795041 -0.080627 -1.438629 0.865262 -0.000984 0.021284 0.979736 0.199157\n10182 54.801907 -0.080860 -1.438507 0.865162 -0.002757 0.022762 0.979728 0.199015\n10183 54.811236 -0.080666 -1.439228 0.865268 -0.000677 0.020848 0.979484 0.200439\n10184 54.820095 -0.080774 -1.438517 0.865230 -0.001027 0.021220 0.979731 0.199188\n10185 54.826694 -0.080789 -1.438435 0.865243 -0.001724 0.021916 0.979764 0.198944\n10186 54.835777 -0.080679 -1.439241 0.865255 -0.000721 0.020888 0.979483 0.200440\n10187 54.845157 -0.080584 -1.438864 0.865254 -0.000891 0.021132 0.979597 0.199856\n10188 54.853054 -0.080797 -1.438430 0.865238 -0.001777 0.021908 0.979760 0.198963\n10189 54.861654 -0.080679 -1.438504 0.865252 -0.000856 0.021222 0.979772 0.198985\n10190 54.869323 -0.080505 -1.438821 0.865254 -0.000490 0.020971 0.979693 0.199401\n10191 54.876811 -0.080630 -1.438539 0.865255 -0.000763 0.021106 0.979764 0.199037\n10192 54.885200 -0.080789 -1.438486 0.865230 -0.001600 0.021667 0.979731 0.199137\n10193 54.894281 -0.080670 -1.438653 0.865220 -0.001575 0.021870 0.979708 0.199225\n10194 54.903283 -0.080607 -1.438605 0.865218 -0.001418 0.021718 0.979701 0.199282\n10195 54.912360 -0.080678 -1.438514 0.865258 -0.000831 0.021219 0.979773 0.198982\n10196 54.918445 -0.080641 -1.438656 0.865218 -0.001495 0.021778 0.979706 0.199249\n10197 54.926802 -0.080613 -1.438612 0.865217 -0.001525 0.021721 0.979706 0.199252\n10198 54.937128 -0.080861 -1.438536 0.865156 -0.002727 0.022838 0.979734 0.198978\n10199 54.944858 -0.080494 -1.438977 0.865095 0.000703 0.020915 0.979763 0.199062\n10200 54.953136 -0.080680 -1.439230 0.865253 -0.000807 0.020951 0.979498 0.200360\n10201 54.961820 -0.080675 -1.438510 0.865255 -0.000891 0.021238 0.979770 0.198994\n10202 54.968430 -0.080634 -1.438531 0.865250 -0.000646 0.021054 0.979772 0.199007\n10203 54.976787 -0.080582 -1.438863 0.865245 -0.001008 0.021195 0.979595 0.199857\n10204 54.984920 -0.080668 -1.438520 0.865260 -0.000782 0.021261 0.979773 0.198980\n10205 54.993259 -0.080664 -1.439207 0.865273 -0.000828 0.021295 0.979515 0.200241\n10206 55.003705 -0.080620 -1.439007 0.865243 -0.000895 0.021418 0.979600 0.199809\n10207 55.010902 -0.080767 -1.438452 0.865243 -0.001550 0.021759 0.979764 0.198962\n10208 55.019726 -0.080618 -1.439067 0.865252 -0.000912 0.021337 0.979550 0.200064\n10209 55.027845 -0.080766 -1.438625 0.865190 -0.002033 0.022293 0.979726 0.199086\n10210 55.035606 -0.080574 -1.438774 0.865244 -0.000990 0.021288 0.979620 0.199727\n10211 55.044771 -0.080589 -1.438983 0.865235 -0.000899 0.021380 0.979601 0.199811\n10212 55.054195 -0.080862 -1.438512 0.865150 -0.002794 0.022827 0.979727 0.199014\n10213 55.061463 -0.080802 -1.438575 0.865175 -0.002356 0.022494 0.979726 0.199061\n10214 55.069344 -0.080714 -1.438609 0.865199 -0.001904 0.022125 0.979719 0.199140\n10215 55.076767 -0.080595 -1.438663 0.865260 -0.000761 0.021232 0.979724 0.199224\n10216 55.086405 -0.080656 -1.439197 0.865241 -0.000794 0.020926 0.979500 0.200352\n10217 55.094899 -0.080864 -1.438511 0.865144 -0.002781 0.022838 0.979728 0.199005\n10218 55.101962 -0.080603 -1.438997 0.865237 -0.000912 0.021442 0.979605 0.199786\n10219 55.111879 -0.080663 -1.438628 0.865206 -0.001607 0.021910 0.979708 0.199223\n10220 55.119256 -0.080574 -1.438737 0.865212 -0.001204 0.021593 0.979674 0.199428\n10221 55.126613 -0.080806 -1.438543 0.865170 -0.002402 0.022551 0.979725 0.199061\n10222 55.136267 -0.080832 -1.438557 0.865147 -0.002611 0.022739 0.979728 0.199019\n10223 55.144413 -0.080572 -1.438869 0.865244 -0.000853 0.021214 0.979588 0.199891\n10224 55.151596 -0.080835 -1.438538 0.865150 -0.002672 0.022725 0.979726 0.199030\n10225 55.161469 -0.080690 -1.439189 0.865231 -0.000819 0.021085 0.979510 0.200286\n10226 55.169692 -0.080602 -1.438942 0.865241 -0.000885 0.021183 0.979570 0.199985\n10227 55.177455 -0.080614 -1.438633 0.865249 -0.000955 0.021327 0.979734 0.199162\n10228 55.187543 -0.080726 -1.438567 0.865196 -0.001946 0.022174 0.979721 0.199128\n10229 55.194050 -0.080667 -1.439175 0.865237 -0.000831 0.021059 0.979512 0.200281\n10230 55.201625 -0.080852 -1.438525 0.865147 -0.002698 0.022777 0.979728 0.199016\n10231 55.211206 -0.080663 -1.439236 0.865240 -0.000742 0.020969 0.979491 0.200392\n10232 55.219299 -0.080667 -1.438664 0.865198 -0.001575 0.021931 0.979712 0.199203\n10233 55.228833 -0.080574 -1.438606 0.865371 0.000250 0.020816 0.979721 0.199284\n10234 55.236337 -0.080568 -1.438560 0.865220 -0.000206 0.020788 0.979775 0.199021\n10235 55.243852 -0.080585 -1.438696 0.865243 -0.000847 0.021246 0.979717 0.199255\n10236 55.253030 -0.080770 -1.438453 0.865228 -0.001511 0.021747 0.979763 0.198971\n10237 55.261736 -0.080581 -1.438764 0.865208 -0.001134 0.021660 0.979669 0.199444\n10238 55.270134 -0.080570 -1.438749 0.865230 -0.000993 0.021347 0.979627 0.199685\n10239 55.278301 -0.080251 -1.438411 0.865280 0.000290 0.020615 0.979689 0.199461\n10240 55.285012 -0.080689 -1.439230 0.865227 -0.000793 0.021065 0.979503 0.200322\n10241 55.293428 -0.080631 -1.438630 0.865237 -0.000972 0.021436 0.979738 0.199131\n10242 55.303735 -0.080848 -1.438537 0.865134 -0.002664 0.022878 0.979728 0.199002\n10243 55.311228 -0.080580 -1.438905 0.865215 -0.000964 0.021483 0.979613 0.199741\n10244 55.319959 -0.080659 -1.439198 0.865235 -0.000725 0.021053 0.979494 0.200369\n10245 55.328269 -0.080701 -1.438660 0.865193 -0.001677 0.022084 0.979716 0.199164\n10246 55.334938 -0.080695 -1.439265 0.865224 -0.000732 0.020975 0.979495 0.200375\n10247 55.345465 -0.080735 -1.438380 0.865206 -0.001692 0.022003 0.979758 0.198967\n10248 55.352101 -0.080568 -1.438693 0.865248 -0.000711 0.021230 0.979715 0.199269\n10249 55.361052 -0.080759 -1.438458 0.865225 -0.001347 0.021702 0.979764 0.198971\n10250 55.369187 -0.080808 -1.438526 0.865162 -0.002452 0.022610 0.979724 0.199057\n10251 55.376929 -0.080426 -1.438989 0.865026 0.001416 0.021552 0.979961 0.198017\n10252 55.388288 -0.080615 -1.439046 0.865237 -0.000898 0.021401 0.979557 0.200025\n10253 55.394463 -0.080218 -1.438241 0.865401 -0.000261 0.020250 0.979533 0.200260\n10254 55.402744 -0.080644 -1.438528 0.865234 -0.000647 0.021196 0.979770 0.198999\n10255 55.412155 -0.080684 -1.438462 0.865201 -0.000627 0.021283 0.979759 0.199046\n10256 55.419150 -0.080651 -1.438684 0.865195 -0.001470 0.021898 0.979709 0.199219\n10257 55.426731 -0.080780 -1.438549 0.865167 -0.002324 0.022547 0.979722 0.199076\n10258 55.435584 -0.080590 -1.438915 0.865228 -0.000838 0.021212 0.979570 0.199979\n10259 55.443804 -0.080688 -1.438652 0.865184 -0.001715 0.022063 0.979713 0.199182\n10260 55.451528 -0.080510 -1.438732 0.865219 -0.000924 0.021418 0.979598 0.199820\n10261 55.461277 -0.080569 -1.438701 0.865222 -0.001006 0.021420 0.979646 0.199584\n10262 55.469782 -0.080784 -1.438439 0.865214 -0.001653 0.022001 0.979759 0.198963\n10263 55.476936 -0.080677 -1.439241 0.865234 -0.000731 0.021084 0.979493 0.200371\n10264 55.488194 -0.080557 -1.438900 0.865221 -0.000828 0.021188 0.979573 0.199967\n10265 55.493809 -0.080738 -1.438611 0.865172 -0.001991 0.022319 0.979719 0.199118\n10266 55.501844 -0.080777 -1.438628 0.865162 -0.002155 0.022497 0.979720 0.199092\n10267 55.511378 -0.080683 -1.438545 0.865220 -0.000837 0.021236 0.979745 0.199120\n10268 55.520122 -0.080641 -1.438695 0.865183 -0.001448 0.021910 0.979702 0.199252\n10269 55.527929 -0.080655 -1.439222 0.865223 -0.000724 0.021020 0.979492 0.200380\n10270 55.536173 -0.080581 -1.438465 0.865190 -0.001417 0.021854 0.979717 0.199186\n10271 55.543397 -0.080827 -1.438540 0.865148 -0.002528 0.022728 0.979723 0.199046\n10272 55.555459 -0.080572 -1.438920 0.865222 -0.000829 0.021230 0.979580 0.199930\n10273 55.560388 -0.080561 -1.438706 0.865197 -0.001191 0.021659 0.979674 0.199419\n10274 55.568417 -0.080783 -1.438440 0.865212 -0.001684 0.022020 0.979758 0.198965\n10275 55.577852 -0.080619 -1.438633 0.865195 -0.001515 0.021876 0.979704 0.199245\n10276 55.586189 -0.080560 -1.438844 0.865224 -0.000882 0.021318 0.979595 0.199848\n10277 55.593283 -0.080793 -1.438586 0.865160 -0.002279 0.022638 0.979724 0.199054\n10278 55.604400 -0.080805 -1.438535 0.865151 -0.002419 0.022633 0.979724 0.199054\n10279 55.610945 -0.080845 -1.438535 0.865122 -0.002718 0.022921 0.979726 0.199006\n10280 55.619873 -0.080730 -1.438439 0.865201 -0.001720 0.022141 0.979744 0.199019\n10281 55.628262 -0.080777 -1.438588 0.865157 -0.002203 0.022556 0.979724 0.199066\n10282 55.634967 -0.080652 -1.439184 0.865230 -0.000739 0.021124 0.979501 0.200325\n10283 55.644582 -0.080793 -1.438541 0.865151 -0.002364 0.022592 0.979722 0.199071\n10284 55.652981 -0.080675 -1.439226 0.865248 -0.000775 0.021430 0.979498 0.200309\n10285 55.662003 -0.080702 -1.438494 0.865224 -0.001043 0.021468 0.979765 0.198993\n10286 55.669069 -0.080569 -1.438573 0.865210 -0.000285 0.020973 0.979768 0.199037\n10287 55.677696 -0.080635 -1.438618 0.865226 -0.000951 0.021471 0.979738 0.199126\n10288 55.686144 -0.080742 -1.438596 0.865163 -0.001996 0.022378 0.979720 0.199110\n10289 55.693630 -0.080712 -1.438493 0.865217 -0.001041 0.021488 0.979766 0.198987\n10290 55.705963 -0.080606 -1.439076 0.865220 -0.000829 0.021474 0.979563 0.199984\n10291 55.710688 -0.080763 -1.438460 0.865215 -0.001391 0.021860 0.979763 0.198960\n10292 55.718537 -0.080551 -1.438951 0.865223 -0.000714 0.021247 0.979559 0.200031\n10293 55.728082 -0.080666 -1.439597 0.864614 0.001237 0.020929 0.979865 0.198555\n10294 55.735671 -0.080850 -1.438513 0.865116 -0.002745 0.022964 0.979723 0.199018\n10295 55.743357 -0.080839 -1.438548 0.865125 -0.002621 0.022844 0.979722 0.199037\n10296 55.754128 -0.080795 -1.438561 0.865148 -0.002315 0.022627 0.979724 0.199059\n10297 55.761287 -0.080800 -1.438544 0.865149 -0.002387 0.022613 0.979722 0.199067\n10298 55.769812 -0.080599 -1.439040 0.865218 -0.000834 0.021473 0.979563 0.199987\n10299 55.777944 -0.080573 -1.438601 0.865355 0.000258 0.020953 0.979707 0.199335\n10300 55.784777 -0.080631 -1.439154 0.865218 -0.000741 0.021133 0.979509 0.200288\n10301 55.794463 -0.080848 -1.438536 0.865115 -0.002778 0.022957 0.979720 0.199033\n10302 55.802591 -0.080578 -1.438929 0.865215 -0.000804 0.021249 0.979570 0.199974\n10303 55.810945 -0.080739 -1.438583 0.865157 -0.002074 0.022406 0.979718 0.199113\n10304 55.819302 -0.080643 -1.438647 0.865177 -0.001449 0.021968 0.979700 0.199258\n10305 55.827973 -0.080689 -1.438491 0.865215 -0.000889 0.021482 0.979767 0.198984\n10306 55.835924 -0.080559 -1.438722 0.865220 -0.000688 0.021294 0.979703 0.199317\n10307 55.843653 -0.080657 -1.439238 0.865205 -0.000650 0.021053 0.979493 0.200374\n10308 55.851640 -0.080782 -1.438442 0.865200 -0.001666 0.022079 0.979757 0.198963\n10309 55.860995 -0.080699 -1.438623 0.865165 -0.001714 0.022222 0.979712 0.199167\n10310 55.870114 -0.080578 -1.438959 0.865215 -0.000789 0.021287 0.979551 0.200064\n10311 55.877621 -0.080771 -1.438574 0.865150 -0.002108 0.022502 0.979719 0.199097\n10312 55.884737 -0.080766 -1.438450 0.865205 -0.001443 0.021951 0.979756 0.198983\n10313 55.894602 -0.080676 -1.438501 0.865210 -0.000813 0.021463 0.979764 0.199000\n10314 55.903628 -0.080218 -1.438300 0.865325 0.000176 0.020579 0.979646 0.199677\n10315 55.911390 -0.080626 -1.439021 0.865212 -0.000782 0.021307 0.979537 0.200134\n10316 55.920182 -0.080370 -1.439033 0.865183 0.000237 0.020659 0.979634 0.199726\n10317 55.928008 -0.080500 -1.438714 0.865200 -0.000870 0.021474 0.979587 0.199871\n10318 55.935618 -0.080584 -1.438690 0.865182 -0.001196 0.021803 0.979678 0.199384\n10319 55.945404 -0.080655 -1.438683 0.865173 -0.001422 0.022050 0.979704 0.199227\n10320 55.952360 -0.080740 -1.438594 0.865157 -0.001937 0.022353 0.979716 0.199129\n10321 55.960535 -0.080833 -1.438583 0.865128 -0.002466 0.022918 0.979723 0.199026\n10322 55.969089 -0.080794 -1.438610 0.865140 -0.002250 0.022675 0.979721 0.199065\n10323 55.977664 -0.080644 -1.438676 0.865177 -0.001427 0.022039 0.979702 0.199240\n10324 55.984778 -0.080808 -1.438617 0.865137 -0.002284 0.022744 0.979722 0.199054\n10325 55.993258 -0.080705 -1.438630 0.865162 -0.001774 0.022225 0.979714 0.199159\n10326 56.001545 -0.080755 -1.438439 0.865198 -0.001009 0.021613 0.979766 0.198974\n10327 56.011505 -0.080688 -1.439305 0.865239 -0.000652 0.021463 0.979500 0.200295\n10328 56.019191 -0.080648 -1.439183 0.865198 -0.000686 0.021114 0.979504 0.200316\n10329 56.029713 -0.080576 -1.438833 0.865208 -0.000880 0.021436 0.979597 0.199825\n10330 56.037048 -0.080831 -1.438528 0.865128 -0.002499 0.022790 0.979719 0.199059\n10331 56.044903 -0.080833 -1.438557 0.865126 -0.002449 0.022848 0.979722 0.199039\n10332 56.053896 -0.080579 -1.438753 0.865181 -0.001083 0.021774 0.979670 0.199426\n10333 56.063034 -0.080652 -1.439150 0.865198 -0.000645 0.021197 0.979509 0.200279\n10334 56.071851 -0.080681 -1.438693 0.865167 -0.001488 0.022115 0.979705 0.199216\n10335 56.078417 -0.080789 -1.438435 0.865189 -0.001650 0.022139 0.979754 0.198969\n10336 56.086307 -0.080449 -1.438998 0.864989 0.001584 0.021795 0.979968 0.197951\n10337 56.093793 -0.080574 -1.438909 0.865212 -0.000797 0.021349 0.979576 0.199938\n10338 56.102905 -0.080638 -1.439194 0.865204 -0.000649 0.021130 0.979503 0.200316\n10339 56.110748 -0.080640 -1.439188 0.865203 -0.000659 0.021153 0.979493 0.200362\n10340 56.118111 -0.080722 -1.438475 0.865205 -0.001102 0.021679 0.979762 0.198985\n10341 56.126572 -0.080494 -1.439014 0.865071 0.000728 0.021106 0.979750 0.199109\n10342 56.137754 -0.080652 -1.439170 0.865198 -0.000730 0.021199 0.979508 0.200285\n10343 56.143896 -0.080699 -1.438495 0.865201 -0.000871 0.021575 0.979766 0.198980\n10344 56.152794 -0.080667 -1.439248 0.865225 -0.000676 0.021465 0.979498 0.200306\n10345 56.160527 -0.080664 -1.439263 0.865215 -0.000633 0.021120 0.979483 0.200415\n10346 56.168196 -0.080236 -1.438154 0.865422 -0.000243 0.020496 0.979540 0.200201\n10347 56.178644 -0.080363 -1.439042 0.865151 0.000438 0.020533 0.979656 0.199632\n10348 56.185754 -0.080667 -1.438505 0.865207 -0.000741 0.021435 0.979765 0.199001\n10349 56.193286 -0.080563 -1.438575 0.865192 -0.000191 0.021029 0.979763 0.199055\n10350 56.201437 -0.080584 -1.438693 0.865173 -0.001192 0.021802 0.979681 0.199372\n10351 56.211060 -0.080791 -1.438629 0.865139 -0.002110 0.022669 0.979721 0.199068\n10352 56.218182 -0.080851 -1.438532 0.865111 -0.002674 0.022990 0.979725 0.199006\n10353 56.228398 -0.080811 -1.438595 0.865127 -0.002348 0.022785 0.979721 0.199054\n10354 56.235500 -0.080584 -1.438893 0.865214 -0.000813 0.021429 0.979580 0.199908\n10355 56.243207 -0.080806 -1.438588 0.865124 -0.002316 0.022784 0.979719 0.199064\n10356 56.251475 -0.080585 -1.438749 0.865177 -0.001081 0.021792 0.979673 0.199409\n10357 56.260573 -0.080613 -1.439074 0.865208 -0.000806 0.021581 0.979561 0.199987\n10358 56.268167 -0.080771 -1.438456 0.865193 -0.001496 0.022060 0.979753 0.198984\n10359 56.276545 -0.080523 -1.438777 0.865219 -0.000564 0.021262 0.979672 0.199475\n10360 56.286816 -0.080663 -1.439200 0.865194 -0.000659 0.021166 0.979507 0.200294\n10361 56.293937 -0.080653 -1.439212 0.865192 -0.000601 0.021145 0.979497 0.200345\n10362 56.303062 -0.080616 -1.438649 0.865211 -0.000810 0.021522 0.979726 0.199181\n10363 56.310531 -0.080600 -1.438578 0.865196 -0.000536 0.021363 0.979754 0.199063\n10364 56.318082 -0.080722 -1.438412 0.865188 -0.000883 0.021622 0.979773 0.198937\n10365 56.328623 -0.080744 -1.438631 0.865149 -0.001872 0.022472 0.979717 0.199111\n10366 56.335696 -0.080752 -1.438625 0.865138 -0.001953 0.022508 0.979716 0.199112\n10367 56.343239 -0.080721 -1.438489 0.865198 -0.001284 0.021915 0.979756 0.198989\n10368 56.351655 -0.080565 -1.438587 0.865184 -0.000343 0.021167 0.979754 0.199083\n10369 56.360617 -0.080568 -1.438579 0.865368 0.000236 0.020998 0.979678 0.199474\n10370 56.368154 -0.080697 -1.439250 0.865222 -0.000723 0.021590 0.979510 0.200234\n10371 56.377625 -0.080726 -1.438998 0.865060 0.000264 0.021239 0.979663 0.199525\n10372 56.385650 -0.080781 -1.438436 0.865182 -0.001647 0.022139 0.979753 0.198976\n10373 56.393176 -0.080343 -1.438279 0.865392 -0.000315 0.020669 0.979508 0.200343\n10374 56.402776 -0.080681 -1.438505 0.865192 -0.000800 0.021589 0.979765 0.198983\n10375 56.410868 -0.080585 -1.438916 0.865191 -0.000740 0.021385 0.979579 0.199917\n10376 56.418219 -0.080404 -1.438990 0.865219 -0.000113 0.020920 0.979604 0.199846\n10377 56.426741 -0.080626 -1.439100 0.865198 -0.000650 0.021300 0.979516 0.200237\n10378 56.436659 -0.080640 -1.439175 0.865221 -0.000704 0.021530 0.979504 0.200269\n10379 56.444420 -0.080538 -1.438366 0.865059 -0.000574 0.021997 0.979622 0.199641\n10380 56.452069 -0.080653 -1.439202 0.865200 -0.000628 0.021179 0.979493 0.200363\n10381 56.461563 -0.080811 -1.438599 0.865117 -0.002351 0.022877 0.979722 0.199038\n10382 56.468388 -0.080333 -1.438742 0.865182 -0.000003 0.020612 0.979648 0.199663\n10383 56.477957 -0.080644 -1.439137 0.865201 -0.000701 0.021291 0.979508 0.200278\n10384 56.485463 -0.080500 -1.438542 0.865352 0.000045 0.021252 0.979569 0.199984\n10385 56.494478 -0.080726 -1.438655 0.865141 -0.001773 0.022413 0.979714 0.199137\n10386 56.502199 -0.080831 -1.438580 0.865109 -0.002427 0.022936 0.979724 0.199020\n10387 56.511199 -0.080492 -1.438599 0.865171 -0.000952 0.021683 0.979662 0.199480\n10388 56.519345 -0.080372 -1.438934 0.865014 0.001331 0.021443 0.979906 0.198298\n10389 56.527226 -0.080657 -1.439181 0.865192 -0.000648 0.021246 0.979498 0.200331\n10390 56.536340 -0.080796 -1.438625 0.865116 -0.002198 0.022777 0.979719 0.199065\n10391 56.544795 -0.080850 -1.438524 0.865094 -0.002663 0.023087 0.979721 0.199016\n10392 56.551610 -0.080645 -1.438585 0.865197 -0.000949 0.021696 0.979742 0.199083\n10393 56.560106 -0.080743 -1.438468 0.865187 -0.001173 0.021831 0.979760 0.198979\n10394 56.570243 -0.080580 -1.438720 0.865158 -0.001175 0.021926 0.979682 0.199351\n10395 56.577724 -0.080626 -1.438529 0.865181 -0.000459 0.021311 0.979766 0.199009\n10396 56.586002 -0.080758 -1.438397 0.865167 -0.001261 0.021948 0.979765 0.198940\n10397 56.594389 -0.080836 -1.438577 0.865096 -0.002557 0.023049 0.979720 0.199027\n10398 56.601734 -0.080674 -1.439306 0.865219 -0.000643 0.021615 0.979531 0.200129\n10399 56.611172 -0.080655 -1.438571 0.865191 -0.000945 0.021758 0.979738 0.199094\n10400 56.619153 -0.080777 -1.438602 0.865122 -0.002165 0.022686 0.979716 0.199093\n10401 56.628635 -0.080757 -1.438606 0.865132 -0.001985 0.022633 0.979716 0.199101\n10402 56.636871 -0.080314 -1.438176 0.865471 -0.000439 0.020751 0.979474 0.200498\n10403 56.644622 -0.080568 -1.438944 0.865185 -0.000695 0.021414 0.979566 0.199980\n10404 56.653753 -0.080670 -1.438559 0.865195 -0.001018 0.021788 0.979746 0.199054\n10405 56.661264 -0.080835 -1.438555 0.865096 -0.002601 0.023046 0.979720 0.199027\n10406 56.668922 -0.080669 -1.439233 0.865191 -0.000653 0.021227 0.979496 0.200340\n10407 56.677495 -0.080662 -1.439228 0.865176 -0.000614 0.021225 0.979496 0.200340\n10408 56.686542 -0.080802 -1.438613 0.865114 -0.002246 0.022809 0.979720 0.199055\n10409 56.694632 -0.080659 -1.438559 0.865190 -0.001001 0.021785 0.979741 0.199077\n10410 56.702422 -0.080572 -1.438732 0.865195 -0.000640 0.021536 0.979714 0.199240\n10411 56.710205 -0.080565 -1.438844 0.865183 -0.000797 0.021500 0.979589 0.199856\n10412 56.722338 -0.080765 -1.438449 0.865174 -0.001413 0.022143 0.979755 0.198968\n10413 56.727373 -0.080796 -1.438609 0.865115 -0.002194 0.022815 0.979720 0.199055\n10414 56.735593 -0.080735 -1.438630 0.865128 -0.001831 0.022519 0.979715 0.199121\n10415 56.744748 -0.080583 -1.438918 0.865163 -0.000844 0.021765 0.979629 0.199632\n10416 56.752504 -0.080666 -1.438681 0.865146 -0.001480 0.022264 0.979705 0.199200\n10417 56.762024 -0.080795 -1.438570 0.865116 -0.002289 0.022807 0.979716 0.199075\n10418 56.769217 -0.080810 -1.438564 0.865105 -0.002349 0.022921 0.979721 0.199040\n10419 56.777428 -0.080538 -1.438828 0.865192 -0.000756 0.021480 0.979593 0.199839\n10420 56.784858 -0.080836 -1.438536 0.865087 -0.002615 0.023110 0.979719 0.199022\n10421 56.794635 -0.080657 -1.439226 0.865191 -0.000585 0.021264 0.979488 0.200376\n10422 56.803486 -0.080744 -1.438460 0.865180 -0.001273 0.021982 0.979758 0.198972\n10423 56.811640 -0.080569 -1.438643 0.865185 -0.000538 0.021427 0.979734 0.199152\n10424 56.819117 -0.080291 -1.438387 0.865313 0.000062 0.020807 0.979579 0.199982\n10425 56.828335 -0.080774 -1.438578 0.865119 -0.002162 0.022689 0.979719 0.199077\n10426 56.835597 -0.080591 -1.438866 0.865157 -0.000921 0.021871 0.979652 0.199506\n10427 56.844469 -0.080748 -1.438456 0.865180 -0.001407 0.022153 0.979753 0.198974\n10428 56.852924 -0.080825 -1.438557 0.865100 -0.002447 0.022990 0.979720 0.199035\n10429 56.860883 -0.080653 -1.439182 0.865175 -0.000645 0.021287 0.979505 0.200288\n10430 56.868352 -0.080688 -1.438661 0.865144 -0.001529 0.022304 0.979709 0.199173\n10431 56.876688 -0.080788 -1.438569 0.865109 -0.002270 0.022812 0.979715 0.199080\n10432 56.888154 -0.080664 -1.439199 0.865178 -0.000629 0.021310 0.979504 0.200296\n10433 56.894160 -0.080570 -1.438671 0.865194 -0.000653 0.021519 0.979709 0.199268\n10434 56.901716 -0.080607 -1.438618 0.865151 -0.001295 0.022064 0.979696 0.199269\n10435 56.911687 -0.080648 -1.439182 0.865177 -0.000605 0.021304 0.979511 0.200261\n10436 56.919648 -0.080561 -1.438479 0.865157 -0.001211 0.021960 0.979708 0.199220\n10437 56.926783 -0.080759 -1.438606 0.865126 -0.001989 0.022670 0.979716 0.199098\n10438 56.937135 -0.080559 -1.438891 0.865184 -0.000696 0.021513 0.979580 0.199902\n10439 56.944890 -0.080519 -1.438838 0.865189 -0.000418 0.021408 0.979683 0.199407\n10440 56.952732 -0.080651 -1.439255 0.865218 -0.000614 0.021564 0.979478 0.200393\n10441 56.961401 -0.080787 -1.438631 0.865121 -0.002030 0.022827 0.979716 0.199076\n10442 56.968381 -0.080592 -1.438542 0.865168 -0.000270 0.021282 0.979765 0.199016\n10443 56.978753 -0.080787 -1.438479 0.865164 -0.001435 0.022101 0.979728 0.199103\n10444 56.985684 -0.080592 -1.438654 0.865195 -0.000696 0.021602 0.979709 0.199257\n10445 56.994725 -0.080667 -1.438626 0.865143 -0.001534 0.022305 0.979707 0.199183\n10446 57.001502 -0.080835 -1.438533 0.865087 -0.002589 0.023116 0.979720 0.199015\n10447 57.010984 -0.080718 -1.438664 0.865132 -0.001676 0.022473 0.979713 0.199135\n10448 57.018212 -0.080825 -1.438528 0.865093 -0.002564 0.023044 0.979719 0.199028\n10449 57.026593 -0.080529 -1.438581 0.865163 -0.000074 0.021079 0.979758 0.199071\n10450 57.034843 -0.080758 -1.438454 0.865177 -0.001332 0.022044 0.979755 0.198980\n10451 57.044426 -0.080835 -1.438544 0.865086 -0.002542 0.023107 0.979718 0.199028\n10452 57.053416 -0.080249 -1.438202 0.865411 -0.000197 0.020703 0.979525 0.200256\n10453 57.061398 -0.080731 -1.438472 0.865173 -0.001137 0.021915 0.979759 0.198977\n10454 57.068382 -0.080678 -1.438604 0.865141 -0.001606 0.022314 0.979710 0.199167\n10455 57.077706 -0.080657 -1.438638 0.865140 -0.001506 0.022292 0.979704 0.199199\n10456 57.086427 -0.080682 -1.439103 0.865158 -0.000724 0.021429 0.979550 0.200055\n10457 57.095394 -0.080671 -1.438500 0.865181 -0.000790 0.021651 0.979763 0.198987\n10458 57.102590 -0.080763 -1.438361 0.865151 -0.001694 0.022352 0.979752 0.198956\n10459 57.109698 -0.080635 -1.439220 0.865174 -0.000538 0.021237 0.979491 0.200364\n10460 57.119866 -0.080691 -1.438615 0.865135 -0.001631 0.022373 0.979710 0.199162\n10461 57.128287 -0.080558 -1.438737 0.865150 -0.001019 0.021919 0.979671 0.199408\n10462 57.136306 -0.080592 -1.438541 0.865170 -0.000275 0.021258 0.979766 0.199012\n10463 57.144782 -0.080593 -1.438556 0.865168 -0.000307 0.021330 0.979763 0.199024\n10464 57.151508 -0.080609 -1.439102 0.865175 -0.000674 0.021749 0.979584 0.199853\n10465 57.161211 -0.080788 -1.438582 0.865111 -0.002185 0.022853 0.979715 0.199075\n10466 57.169279 -0.080626 -1.438713 0.865137 -0.001269 0.022140 0.979694 0.199269\n10467 57.178705 -0.080571 -1.438935 0.865178 -0.000685 0.021458 0.979561 0.200000\n10468 57.186870 -0.080595 -1.438656 0.865186 -0.000727 0.021657 0.979716 0.199214\n10469 57.195265 -0.080658 -1.439219 0.865168 -0.000552 0.021293 0.979492 0.200357\n10470 57.203196 -0.080748 -1.438615 0.865115 -0.001955 0.022686 0.979713 0.199107\n10471 57.211298 -0.080721 -1.438589 0.865126 -0.001818 0.022532 0.979712 0.199130\n10472 57.219187 -0.080659 -1.438505 0.865168 -0.000641 0.021611 0.979762 0.198993\n10473 57.227855 -0.080561 -1.438923 0.865176 -0.000653 0.021506 0.979567 0.199965\n10474 57.236178 -0.080741 -1.438639 0.865115 -0.001868 0.022661 0.979711 0.199122\n10475 57.245038 -0.080555 -1.438715 0.865144 -0.001035 0.021947 0.979674 0.199390\n10476 57.252383 -0.080771 -1.438437 0.865157 -0.001470 0.022242 0.979751 0.198976\n10477 57.259918 -0.080745 -1.438639 0.865112 -0.001929 0.022678 0.979712 0.199116\n10478 57.270254 -0.080625 -1.438666 0.865138 -0.001284 0.022155 0.979697 0.199253\n10479 57.277889 -0.080641 -1.439237 0.865169 -0.000539 0.021301 0.979495 0.200338\n10480 57.285936 -0.080654 -1.439178 0.865163 -0.000594 0.021380 0.979509 0.200262\n10481 57.295157 -0.080785 -1.438645 0.865104 -0.002081 0.022892 0.979720 0.199050\n10482 57.301494 -0.080739 -1.438574 0.865119 -0.001894 0.022659 0.979714 0.199108\n10483 57.311695 -0.080560 -1.438794 0.865146 -0.000885 0.021895 0.979653 0.199498\n10484 57.319378 -0.080789 -1.438430 0.865160 -0.001603 0.022299 0.979749 0.198976\n10485 57.327675 -0.080640 -1.438521 0.865162 -0.000513 0.021471 0.979764 0.199003\n10486 57.337108 -0.080541 -1.438846 0.865172 -0.000655 0.021555 0.979592 0.199838\n10487 57.345286 -0.080640 -1.438784 0.865134 -0.001129 0.022151 0.979694 0.199271\n10488 57.353250 -0.080595 -1.438805 0.865133 -0.001026 0.022003 0.979676 0.199376\n10489 57.361338 -0.080708 -1.438992 0.865041 0.000354 0.021426 0.979657 0.199534\n10490 57.369162 -0.080557 -1.438728 0.865171 -0.000549 0.021600 0.979714 0.199232\n10491 57.377882 -0.080785 -1.438588 0.865101 -0.002148 0.022903 0.979718 0.199059\n10492 57.386225 -0.080684 -1.438634 0.865125 -0.001633 0.022432 0.979709 0.199161\n10493 57.394678 -0.080564 -1.438941 0.865170 -0.000644 0.021501 0.979559 0.200003\n10494 57.402567 -0.080836 -1.438577 0.865066 -0.002504 0.023240 0.979718 0.199011\n10495 57.409815 -0.080618 -1.439517 0.864618 0.001430 0.021284 0.979897 0.198359\n10496 57.418069 -0.080252 -1.438505 0.865187 0.000610 0.021038 0.979715 0.199288\n10497 57.426716 -0.080560 -1.438831 0.865158 -0.000711 0.021668 0.979599 0.199788\n10498 57.436480 -0.080744 -1.438456 0.865154 -0.001324 0.022159 0.979752 0.198982\n10499 57.444165 -0.080678 -1.438537 0.865161 -0.001025 0.021919 0.979748 0.199029\n10500 57.452867 -0.080622 -1.438670 0.865129 -0.001275 0.022207 0.979698 0.199243\n10501 57.460865 -0.080611 -1.438600 0.865146 -0.000962 0.021889 0.979688 0.199330\n10502 57.468106 -0.080588 -1.438662 0.865173 -0.000613 0.021723 0.979727 0.199156\n10503 57.478233 -0.080742 -1.438589 0.865110 -0.001974 0.022679 0.979711 0.199118\n10504 57.485533 -0.080782 -1.438624 0.865098 -0.002092 0.022884 0.979713 0.199082\n10505 57.494504 -0.080467 -1.438697 0.865181 -0.000367 0.021360 0.979658 0.199533\n10506 57.502856 -0.080697 -1.438397 0.865156 -0.000905 0.021832 0.979766 0.198948\n10507 57.510641 -0.080599 -1.439060 0.865161 -0.000670 0.021799 0.979569 0.199924\n10508 57.519868 -0.080813 -1.438598 0.865089 -0.002281 0.023044 0.979715 0.199053\n10509 57.527487 -0.080619 -1.438807 0.865124 -0.001055 0.022180 0.979690 0.199287\n10510 57.536141 -0.080573 -1.438904 0.865161 -0.000680 0.021589 0.979572 0.199928\n10511 57.544099 -0.080436 -1.438737 0.865142 0.000116 0.021032 0.979718 0.199273\n10512 57.551534 -0.080610 -1.439192 0.865168 -0.000490 0.021354 0.979487 0.200374\n10513 57.559842 -0.080665 -1.438602 0.865122 -0.001588 0.022382 0.979707 0.199175\n10514 57.569482 -0.080833 -1.438532 0.865063 -0.002601 0.023191 0.979714 0.199039\n10515 57.577281 -0.080621 -1.439493 0.864622 0.001458 0.021371 0.979902 0.198328\n10516 57.586078 -0.080649 -1.439210 0.865147 -0.000544 0.021339 0.979504 0.200290\n10517 57.595050 -0.080822 -1.438543 0.865073 -0.002420 0.023119 0.979714 0.199050\n10518 57.601583 -0.080776 -1.438490 0.865136 -0.001351 0.022147 0.979716 0.199158\n10519 57.611639 -0.080681 -1.438669 0.865113 -0.001500 0.022410 0.979709 0.199162\n10520 57.619252 -0.080487 -1.438599 0.865304 0.000130 0.021414 0.979560 0.200011\n10521 57.628034 -0.080446 -1.439221 0.865179 0.000172 0.021119 0.979567 0.200008\n10522 57.636317 -0.080654 -1.438434 0.865116 -0.001618 0.022492 0.979722 0.199090\n10523 57.644385 -0.080777 -1.438492 0.865133 -0.001391 0.022137 0.979717 0.199152\n10524 57.652854 -0.080735 -1.438459 0.865152 -0.001193 0.022118 0.979755 0.198971\n10525 57.660853 -0.080692 -1.438675 0.865110 -0.001593 0.022518 0.979706 0.199167\n10526 57.668210 -0.080742 -1.438472 0.865152 -0.001364 0.022249 0.979748 0.198990\n10527 57.677086 -0.080718 -1.438642 0.865106 -0.001752 0.022601 0.979709 0.199141\n10528 57.686410 -0.080750 -1.438648 0.865094 -0.001964 0.022800 0.979709 0.199115\n10529 57.693173 -0.080836 -1.438542 0.865061 -0.002605 0.023257 0.979713 0.199032\n10530 57.701652 -0.080544 -1.438708 0.865173 -0.000486 0.021598 0.979686 0.199372\n10531 57.710967 -0.080652 -1.438685 0.865115 -0.001398 0.022356 0.979704 0.199192\n10532 57.718207 -0.080566 -1.438564 0.865146 -0.000142 0.021334 0.979761 0.199031\n10533 57.726618 -0.080822 -1.438545 0.865066 -0.002445 0.023227 0.979717 0.199022\n10534 57.735973 -0.080772 -1.438440 0.865143 -0.001456 0.022293 0.979750 0.198974\n10535 57.744741 -0.080654 -1.439252 0.865146 -0.000483 0.021342 0.979493 0.200347\n10536 57.752759 -0.080821 -1.438578 0.865067 -0.002481 0.023142 0.979712 0.199054\n10537 57.760395 -0.080560 -1.438720 0.865126 -0.000991 0.022027 0.979669 0.199407\n10538 57.769656 -0.080669 -1.439252 0.865149 -0.000532 0.021413 0.979494 0.200330\n10539 57.778356 -0.080577 -1.438658 0.865165 -0.000637 0.021698 0.979712 0.199231\n10540 57.785120 -0.080675 -1.438541 0.865152 -0.001040 0.022043 0.979744 0.199036\n10541 57.794591 -0.080750 -1.438450 0.865152 -0.001266 0.022157 0.979752 0.198980\n10542 57.802001 -0.080565 -1.438720 0.865119 -0.001064 0.022056 0.979675 0.199372\n10543 57.809955 -0.080708 -1.438676 0.865106 -0.001607 0.022573 0.979705 0.199161\n10544 57.818085 -0.080786 -1.438609 0.865072 -0.002277 0.023008 0.979710 0.199085\n10545 57.827581 -0.080523 -1.438770 0.865169 -0.000449 0.021552 0.979676 0.199425\n10546 57.836218 -0.080664 -1.439284 0.865146 -0.000485 0.021359 0.979486 0.200378\n10547 57.843359 -0.080589 -1.438549 0.865145 -0.000260 0.021432 0.979759 0.199028\n10548 57.852890 -0.080600 -1.438687 0.865115 -0.001188 0.022184 0.979689 0.199287\n10549 57.860302 -0.080839 -1.438549 0.865055 -0.002609 0.023246 0.979712 0.199043\n10550 57.868324 -0.080594 -1.438662 0.865160 -0.000741 0.021761 0.979711 0.199229\n10551 57.876900 -0.080567 -1.438763 0.865156 -0.000495 0.021702 0.979705 0.199267\n10552 57.886204 -0.080829 -1.438576 0.865050 -0.002535 0.023271 0.979710 0.199049\n10553 57.894929 -0.080676 -1.438541 0.865144 -0.000677 0.021694 0.979738 0.199103\n10554 57.902960 -0.080555 -1.438876 0.865153 -0.000654 0.021635 0.979580 0.199887\n10555 57.911493 -0.080788 -1.438618 0.865076 -0.002164 0.023013 0.979713 0.199068\n10556 57.918535 -0.080754 -1.438585 0.865090 -0.002032 0.022782 0.979711 0.199108\n10557 57.927924 -0.080806 -1.438543 0.865070 -0.002403 0.023072 0.979711 0.199067\n10558 57.936155 -0.080668 -1.438668 0.865109 -0.001461 0.022434 0.979706 0.199175\n10559 57.943300 -0.080760 -1.438501 0.865128 -0.001288 0.022136 0.979714 0.199171\n10560 57.952143 -0.080746 -1.438395 0.865090 -0.002150 0.022886 0.979723 0.199034\n10561 57.961503 -0.080552 -1.438724 0.865161 -0.000559 0.021655 0.979698 0.199307\n10562 57.968438 -0.080599 -1.438613 0.865143 -0.000967 0.021957 0.979679 0.199364\n10563 57.977738 -0.080693 -1.439003 0.865021 0.000408 0.021492 0.979660 0.199511\n10564 57.985659 -0.080629 -1.439150 0.865149 -0.000547 0.021492 0.979508 0.200256\n10565 57.993204 -0.080769 -1.438639 0.865088 -0.001994 0.022924 0.979713 0.199083\n10566 58.001997 -0.080641 -1.438385 0.865118 -0.000508 0.021759 0.979774 0.198922\n10567 58.011062 -0.080703 -1.438670 0.865100 -0.001582 0.022570 0.979707 0.199156\n10568 58.018472 -0.080739 -1.438599 0.865092 -0.001949 0.022809 0.979711 0.199103\n10569 58.026601 -0.080740 -1.438686 0.865087 -0.001784 0.022732 0.979710 0.199120\n10570 58.034929 -0.080552 -1.438857 0.865144 -0.000662 0.021691 0.979587 0.199844\n10571 58.044672 -0.080652 -1.439157 0.865141 -0.000583 0.021540 0.979519 0.200198\n10572 58.053400 -0.080566 -1.438921 0.865124 -0.000657 0.021591 0.979576 0.199910\n10573 58.060535 -0.080705 -1.439001 0.865019 0.000397 0.021504 0.979655 0.199533\n10574 58.069603 -0.080535 -1.438761 0.865141 -0.000734 0.021768 0.979623 0.199659\n10575 58.076399 -0.080679 -1.439232 0.865135 -0.000552 0.021523 0.979505 0.200267\n10576 58.086141 -0.080759 -1.438451 0.865134 -0.001422 0.022384 0.979747 0.198979\n10577 58.094799 -0.080668 -1.438600 0.865099 -0.001565 0.022516 0.979705 0.199170\n10578 58.101550 -0.080803 -1.438623 0.865055 -0.002266 0.023151 0.979713 0.199054\n10579 58.110132 -0.080537 -1.438519 0.865318 0.000269 0.021291 0.979669 0.199486\n10580 58.121062 -0.080761 -1.438620 0.865077 -0.002065 0.022852 0.979708 0.199112\n10581 58.127910 -0.080734 -1.438459 0.865136 -0.001157 0.022153 0.979752 0.198982\n10582 58.135873 -0.080802 -1.438643 0.865070 -0.002123 0.023093 0.979712 0.199063\n10583 58.144639 -0.080730 -1.438670 0.865079 -0.001784 0.022748 0.979709 0.199121\n10584 58.151681 -0.080553 -1.438925 0.865138 -0.000720 0.021899 0.979600 0.199759\n10585 58.161023 -0.080562 -1.438778 0.865114 -0.000941 0.022112 0.979668 0.199401\n10586 58.169319 -0.080676 -1.439267 0.865126 -0.000497 0.021425 0.979503 0.200287\n10587 58.178197 -0.080756 -1.438627 0.865078 -0.002032 0.022910 0.979707 0.199113\n10588 58.186146 -0.080559 -1.438875 0.865141 -0.000670 0.021713 0.979587 0.199844\n10589 58.194408 -0.080730 -1.438589 0.865089 -0.001871 0.022763 0.979708 0.199127\n10590 58.202819 -0.080772 -1.438609 0.865075 -0.002076 0.022986 0.979711 0.199084\n10591 58.211145 -0.080815 -1.438565 0.865051 -0.002414 0.023205 0.979710 0.199058\n10592 58.218360 -0.080672 -1.438689 0.865096 -0.001446 0.022520 0.979702 0.199186\n10593 58.227075 -0.080697 -1.438522 0.865139 -0.001098 0.022114 0.979743 0.199030\n10594 58.236349 -0.080821 -1.438540 0.865042 -0.002575 0.023276 0.979709 0.199051\n10595 58.243258 -0.080798 -1.438656 0.865061 -0.002111 0.023086 0.979710 0.199077\n10596 58.251471 -0.080689 -1.438636 0.865090 -0.001626 0.022617 0.979707 0.199146\n10597 58.261310 -0.080570 -1.438927 0.865122 -0.000620 0.021648 0.979571 0.199931\n10598 58.268304 -0.080569 -1.438918 0.865128 -0.000659 0.021670 0.979577 0.199896\n10599 58.276686 -0.080677 -1.438511 0.865136 -0.000893 0.021962 0.979751 0.199011\n10600 58.286143 -0.080576 -1.438943 0.865124 -0.000649 0.021665 0.979570 0.199930\n10601 58.293757 -0.080629 -1.439200 0.865167 -0.000559 0.021764 0.979477 0.200379\n10602 58.302951 -0.080532 -1.438839 0.865138 -0.000598 0.021700 0.979593 0.199818\n10603 58.310303 -0.080767 -1.438619 0.865070 -0.002077 0.023019 0.979707 0.199097\n10604 58.319132 -0.080407 -1.439097 0.865138 0.000223 0.021240 0.979618 0.199742\n10605 58.329049 -0.080703 -1.438482 0.865136 -0.000920 0.021980 0.979753 0.198999\n10606 58.335929 -0.080579 -1.438669 0.865122 -0.000909 0.021910 0.979651 0.199508\n10607 58.345493 -0.080526 -1.438823 0.865130 -0.000655 0.021753 0.979601 0.199771\n10608 58.351995 -0.080781 -1.438603 0.865067 -0.002114 0.023040 0.979713 0.199068\n10609 58.359993 -0.080555 -1.438985 0.865132 -0.000669 0.021947 0.979589 0.199807\n10610 58.369061 -0.080701 -1.438705 0.865084 -0.001571 0.022601 0.979703 0.199171\n10611 58.378080 -0.080653 -1.439229 0.865126 -0.000507 0.021505 0.979501 0.200286\n10612 58.385133 -0.080547 -1.438865 0.865131 -0.000627 0.021745 0.979591 0.199823\n10613 58.393378 -0.080795 -1.438592 0.865051 -0.002270 0.023173 0.979708 0.199075\n10614 58.402978 -0.080653 -1.439434 0.864679 0.001376 0.021621 0.979885 0.198384\n10615 58.410341 -0.080808 -1.438594 0.865044 -0.002310 0.023267 0.979711 0.199049\n10616 58.419681 -0.080538 -1.438584 0.865273 0.000480 0.021178 0.979678 0.199454\n10617 58.428345 -0.080785 -1.438598 0.865059 -0.002225 0.023110 0.979709 0.199076\n10618 58.435059 -0.080728 -1.438687 0.865077 -0.001722 0.022793 0.979706 0.199131\n10619 58.443307 -0.080669 -1.439189 0.865111 -0.000528 0.021540 0.979517 0.200205\n10620 58.453093 -0.080611 -1.438525 0.865126 -0.000437 0.021682 0.979756 0.199017\n10621 58.461043 -0.080618 -1.438534 0.865120 -0.000365 0.021619 0.979754 0.199033\n10622 58.468329 -0.080655 -1.439200 0.865117 -0.000546 0.021582 0.979511 0.200228\n10623 58.478665 -0.080706 -1.438709 0.865078 -0.001544 0.022703 0.979703 0.199157\n10624 58.485516 -0.080563 -1.438899 0.865120 -0.000645 0.021738 0.979572 0.199914\n10625 58.494225 -0.080581 -1.438797 0.865103 -0.000914 0.022165 0.979666 0.199405\n10626 58.501602 -0.080678 -1.438497 0.865124 -0.000711 0.021913 0.979753 0.199007\n10627 58.511401 -0.080568 -1.438647 0.865118 -0.000867 0.021965 0.979665 0.199433\n10628 58.518509 -0.080800 -1.438565 0.865054 -0.002307 0.023179 0.979710 0.199061\n10629 58.527093 -0.080580 -1.438727 0.865130 -0.000547 0.021824 0.979712 0.199216\n10630 58.535727 -0.080575 -1.438884 0.865120 -0.000690 0.021757 0.979582 0.199864\n10631 58.543390 -0.080809 -1.438585 0.865036 -0.002404 0.023287 0.979705 0.199072\n10632 58.553327 -0.080819 -1.438600 0.865040 -0.002341 0.023293 0.979710 0.199048\n10633 58.560598 -0.080221 -1.438257 0.865300 -0.000102 0.020741 0.979505 0.200350\n10634 58.568268 -0.080711 -1.438649 0.865077 -0.001741 0.022751 0.979702 0.199157\n10635 58.576996 -0.080561 -1.438728 0.865129 -0.000495 0.021819 0.979712 0.199221\n10636 58.585908 -0.080804 -1.438592 0.865050 -0.002293 0.023181 0.979709 0.199069\n10637 58.593087 -0.080762 -1.438651 0.865059 -0.001953 0.023008 0.979707 0.199103\n10638 58.603058 -0.080511 -1.438841 0.865127 -0.000665 0.021852 0.979548 0.200021\n10639 58.611799 -0.080614 -1.438532 0.865122 -0.000326 0.021646 0.979759 0.199009\n10640 58.619550 -0.080732 -1.438653 0.865067 -0.001833 0.022846 0.979706 0.199124\n10641 58.627506 -0.080636 -1.438607 0.865134 -0.000801 0.022006 0.979725 0.199135\n10642 58.636199 -0.080776 -1.438626 0.865055 -0.002081 0.023073 0.979707 0.199093\n10643 58.643745 -0.080758 -1.438685 0.865065 -0.001877 0.022968 0.979704 0.199119\n10644 58.652176 -0.080768 -1.438598 0.865056 -0.002131 0.023035 0.979707 0.199096\n10645 58.661042 -0.080656 -1.438580 0.865134 -0.000841 0.022036 0.979735 0.199082\n10646 58.669051 -0.080740 -1.438625 0.865063 -0.001941 0.022938 0.979706 0.199112\n10647 58.676497 -0.080583 -1.438680 0.865126 -0.000528 0.021883 0.979719 0.199178\n10648 58.685497 -0.080654 -1.438749 0.865076 -0.001324 0.022511 0.979695 0.199222\n10649 58.694566 -0.080828 -1.438591 0.865023 -0.002461 0.023456 0.979706 0.199045\n10650 58.701703 -0.080773 -1.438613 0.865057 -0.002073 0.023059 0.979707 0.199092\n10651 58.709867 -0.080826 -1.438604 0.865017 -0.002489 0.023418 0.979704 0.199060\n10652 58.720120 -0.080289 -1.438328 0.865287 -0.000062 0.020934 0.979506 0.200322\n10653 58.727108 -0.080819 -1.438567 0.865028 -0.002461 0.023398 0.979706 0.199054\n10654 58.736656 -0.080569 -1.438936 0.865118 -0.000605 0.021761 0.979568 0.199934\n10655 58.743566 -0.080118 -1.438235 0.865240 0.000132 0.020587 0.979554 0.200124\n10656 58.751521 -0.080765 -1.438618 0.865060 -0.002022 0.023023 0.979708 0.199092\n10657 58.760675 -0.080558 -1.438955 0.865110 -0.000570 0.021703 0.979560 0.199979\n10658 58.769661 -0.080697 -1.438962 0.865044 0.000553 0.021494 0.979645 0.199585\n10659 58.777755 -0.080693 -1.438989 0.865003 0.000443 0.021594 0.979652 0.199536\n10660 58.785721 -0.080586 -1.438925 0.865101 -0.000624 0.021757 0.979567 0.199939\n10661 58.793139 -0.080702 -1.438722 0.865067 -0.001517 0.022741 0.979702 0.199159\n10662 58.801601 -0.080812 -1.438630 0.865032 -0.002271 0.023301 0.979711 0.199044\n10663 58.811366 -0.080597 -1.438539 0.865111 -0.000306 0.021649 0.979753 0.199037\n10664 58.818916 -0.080820 -1.438596 0.865023 -0.002390 0.023377 0.979709 0.199042\n10665 58.827845 -0.080711 -1.438692 0.865069 -0.001594 0.022770 0.979701 0.199162\n10666 58.835748 -0.080633 -1.438597 0.865130 -0.000738 0.022031 0.979726 0.199127\n10667 58.843261 -0.080660 -1.439323 0.865147 -0.000434 0.021908 0.979510 0.200201\n10668 58.851487 -0.080475 -1.438721 0.865111 0.000025 0.021463 0.979715 0.199243\n10669 58.859948 -0.080817 -1.438589 0.865023 -0.002417 0.023384 0.979705 0.199064\n10670 58.869632 -0.080708 -1.438623 0.865069 -0.001691 0.022804 0.979701 0.199157\n10671 58.877649 -0.080674 -1.438669 0.865082 -0.001404 0.022626 0.979699 0.199190\n10672 58.886272 -0.080691 -1.438526 0.865112 -0.001101 0.022254 0.979741 0.199027\n10673 58.894796 -0.080591 -1.438668 0.865129 -0.000606 0.021907 0.979702 0.199256\n10674 58.901813 -0.080549 -1.438804 0.865107 -0.000675 0.021850 0.979600 0.199764\n10675 58.910001 -0.080830 -1.438591 0.865016 -0.002466 0.023428 0.979705 0.199054\n10676 58.918242 -0.080600 -1.438672 0.865119 -0.000662 0.021950 0.979719 0.199172\n10677 58.928559 -0.080564 -1.438864 0.865108 -0.000661 0.021815 0.979585 0.199843\n10678 58.936060 -0.080785 -1.438674 0.865039 -0.002039 0.023169 0.979710 0.199067\n10679 58.945227 -0.080650 -1.438747 0.865073 -0.001204 0.022486 0.979692 0.199243\n10680 58.953508 -0.080748 -1.438509 0.865084 -0.001214 0.022273 0.979705 0.199198\n10681 58.961866 -0.080732 -1.438667 0.865054 -0.001758 0.022858 0.979701 0.199152\n10682 58.969752 -0.080742 -1.438626 0.865057 -0.001845 0.022896 0.979703 0.199136\n10683 58.977520 -0.080340 -1.438284 0.865347 -0.000240 0.021067 0.979475 0.200463\n10684 58.986159 -0.080170 -1.438322 0.865204 0.000103 0.020627 0.979539 0.200194\n10685 58.994502 -0.080673 -1.438492 0.865109 -0.000739 0.021988 0.979750 0.199012\n10686 59.001504 -0.080659 -1.439210 0.865105 -0.000562 0.021639 0.979508 0.200239\n10687 59.011238 -0.080626 -1.438514 0.865106 -0.000401 0.021760 0.979755 0.199016\n10688 59.019792 -0.080742 -1.438636 0.865053 -0.001887 0.022931 0.979702 0.199134\n10689 59.028034 -0.080763 -1.438660 0.865054 -0.001884 0.023040 0.979705 0.199109\n10690 59.036120 -0.080637 -1.438668 0.865076 -0.001311 0.022519 0.979692 0.199236\n10691 59.044183 -0.080726 -1.438740 0.865051 -0.001605 0.022876 0.979702 0.199141\n10692 59.054486 -0.080557 -1.438535 0.865266 0.000196 0.021473 0.979612 0.199748\n10693 59.060235 -0.080624 -1.439430 0.864660 0.001390 0.021625 0.979878 0.198417\n10694 59.069525 -0.080586 -1.438545 0.865101 -0.000240 0.021619 0.979751 0.199050\n10695 59.078169 -0.080557 -1.438724 0.865101 -0.000759 0.021930 0.979631 0.199604\n10696 59.085235 -0.080569 -1.438867 0.865078 -0.000824 0.022208 0.979654 0.199458\n10697 59.093114 -0.080699 -1.438662 0.865063 -0.001577 0.022800 0.979698 0.199173\n10698 59.103459 -0.080797 -1.438627 0.865021 -0.002340 0.023307 0.979701 0.199090\n10699 59.111160 -0.080811 -1.438622 0.865024 -0.002287 0.023327 0.979705 0.199072\n10700 59.119254 -0.080825 -1.438584 0.865009 -0.002464 0.023474 0.979704 0.199054\n10701 59.128829 -0.080265 -1.438364 0.865229 0.000101 0.020975 0.979538 0.200163\n10702 59.135150 -0.080659 -1.439234 0.865090 -0.000442 0.021638 0.979511 0.200226\n10703 59.143147 -0.080660 -1.439214 0.865092 -0.000493 0.021666 0.979497 0.200290\n10704 59.153055 -0.080701 -1.438752 0.865061 -0.001420 0.022784 0.979700 0.199163\n10705 59.160942 -0.080656 -1.438747 0.865063 -0.001302 0.022607 0.979691 0.199231\n10706 59.169383 -0.080819 -1.438581 0.865008 -0.002522 0.023511 0.979700 0.199069\n10707 59.178495 -0.080633 -1.439230 0.865101 -0.000403 0.021595 0.979499 0.200290\n10708 59.184822 -0.080733 -1.438704 0.865055 -0.001679 0.022930 0.979703 0.199133\n10709 59.194152 -0.080799 -1.438643 0.865019 -0.002257 0.023368 0.979703 0.199074\n10710 59.202235 -0.080666 -1.439246 0.865097 -0.000404 0.021598 0.979502 0.200271\n10711 59.211131 -0.080653 -1.439238 0.865093 -0.000467 0.021641 0.979499 0.200283\n10712 59.219680 -0.080384 -1.438033 0.865309 -0.000135 0.021568 0.979566 0.199966\n10713 59.227652 -0.080752 -1.438694 0.865036 -0.001925 0.023089 0.979702 0.199114\n10714 59.236004 -0.080790 -1.438724 0.865035 -0.001922 0.023175 0.979707 0.199079\n10715 59.244695 -0.080816 -1.438601 0.865011 -0.002408 0.023503 0.979702 0.199063\n10716 59.251604 -0.080549 -1.438765 0.865107 -0.000429 0.021863 0.979702 0.199262\n10717 59.260036 -0.080654 -1.439260 0.865139 -0.000474 0.021998 0.979514 0.200171\n10718 59.269509 -0.080581 -1.438375 0.865079 -0.000398 0.021851 0.979766 0.198952\n10719 59.277337 -0.080764 -1.438621 0.865036 -0.002057 0.023085 0.979702 0.199115\n10720 59.285948 -0.080799 -1.438644 0.865009 -0.002330 0.023480 0.979703 0.199059\n10721 59.294695 -0.080543 -1.438805 0.865097 -0.000613 0.021942 0.979602 0.199746\n10722 59.301657 -0.080733 -1.438453 0.865095 -0.001166 0.022432 0.979745 0.198987\n10723 59.311450 -0.080640 -1.438502 0.865097 -0.000469 0.021900 0.979755 0.198999\n10724 59.319409 -0.080631 -1.438787 0.865063 -0.001095 0.022538 0.979688 0.199253\n10725 59.327688 -0.080701 -1.438689 0.865055 -0.001544 0.022783 0.979699 0.199171\n10726 59.335882 -0.080758 -1.438438 0.865089 -0.001400 0.022612 0.979741 0.198983\n10727 59.345375 -0.080660 -1.439331 0.865138 -0.000430 0.021979 0.979496 0.200263\n10728 59.352057 -0.080826 -1.438585 0.865007 -0.002505 0.023565 0.979705 0.199040\n10729 59.361775 -0.080815 -1.438624 0.864999 -0.002382 0.023502 0.979703 0.199057\n10730 59.368782 -0.080406 -1.439002 0.864910 0.001156 0.021279 0.979751 0.199084\n10731 59.376477 -0.080740 -1.438418 0.865079 -0.001477 0.022668 0.979735 0.199005\n10732 59.384775 -0.080649 -1.439276 0.865135 -0.000503 0.021919 0.979465 0.200417\n10733 59.393526 -0.080546 -1.438713 0.865091 -0.000760 0.022013 0.979634 0.199579\n"
  },
  {
    "path": "matlab/data/RAW_IMU_DATA_matlab.txt",
    "content": "4814 0.000000 -0.003638 -0.002836 -0.009831 0.766352 0.880101 10.027621\n4815 0.004458 -0.003813 -0.002984 -0.009896 0.757859 0.893670 10.018570\n4816 0.011112 -0.003347 -0.002591 -0.011155 0.754778 0.894775 10.005535\n4817 0.016578 -0.003385 -0.002526 -0.011604 0.757826 0.901588 10.008098\n4818 0.023173 -0.003476 -0.001901 -0.011452 0.750915 0.901768 10.011896\n4819 0.028749 -0.003686 -0.001222 -0.011507 0.759079 0.870996 10.025348\n4820 0.035191 -0.004054 -0.002062 -0.011030 0.772590 0.851013 10.017776\n4821 0.040855 -0.003930 -0.002406 -0.010832 0.766805 0.866316 10.028804\n4822 0.047185 -0.003598 -0.002469 -0.010577 0.752896 0.888350 10.032959\n4823 0.052930 -0.003114 -0.002346 -0.010001 0.740652 0.899633 10.009249\n4824 0.059309 -0.004063 -0.001801 -0.010057 0.741207 0.879555 10.013741\n4825 0.064879 -0.004444 -0.001537 -0.010290 0.748296 0.884094 10.017251\n4826 0.071373 -0.003936 -0.001402 -0.011011 0.775556 0.879719 10.029593\n4827 0.077143 -0.003531 -0.001467 -0.011208 0.784613 0.863523 10.036070\n4828 0.083370 -0.003070 -0.001994 -0.010617 0.777650 0.855358 10.039581\n4829 0.089213 -0.002944 -0.001821 -0.010245 0.766654 0.863879 10.031919\n4830 0.095560 -0.002799 -0.001640 -0.010060 0.754904 0.871807 10.021008\n4831 0.101225 -0.003240 -0.001806 -0.010342 0.755588 0.869307 10.019308\n4832 0.107323 -0.004014 -0.002083 -0.011091 0.759739 0.895267 10.001467\n4833 0.113205 -0.004102 -0.002024 -0.011504 0.758279 0.905987 9.994713\n4834 0.119597 -0.004062 -0.001829 -0.011505 0.753245 0.873033 9.994442\n4835 0.125386 -0.003927 -0.001966 -0.011005 0.760083 0.862591 9.993141\n4836 0.131515 -0.003466 -0.002514 -0.010400 0.764028 0.892052 9.997518\n4837 0.137402 -0.003297 -0.002945 -0.010424 0.761405 0.900020 10.005370\n4838 0.143637 -0.003648 -0.003399 -0.010562 0.773372 0.887097 10.013227\n4839 0.149516 -0.003907 -0.003007 -0.010634 0.772223 0.895351 10.007657\n4840 0.155747 -0.003758 -0.001931 -0.010813 0.757536 0.920462 9.999290\n4841 0.161631 -0.003954 -0.001536 -0.010878 0.764535 0.911653 9.994086\n4842 0.167756 -0.004052 -0.001308 -0.010979 0.787300 0.869684 9.991043\n4843 0.173572 -0.004026 -0.001593 -0.010856 0.783147 0.867155 9.989739\n4844 0.179720 -0.003818 -0.002016 -0.010472 0.759171 0.893398 10.011199\n4845 0.185734 -0.003898 -0.002164 -0.010241 0.753804 0.900328 10.013746\n4846 0.191904 -0.004375 -0.001895 -0.010336 0.765888 0.897608 9.994632\n4847 0.197999 -0.004533 -0.001576 -0.010670 0.773051 0.901168 9.993672\n4848 0.204008 -0.003955 -0.001207 -0.010881 0.775498 0.900918 10.005406\n4849 0.210014 -0.003866 -0.001397 -0.010944 0.777465 0.887753 10.011246\n4850 0.216104 -0.003911 -0.002589 -0.010419 0.767344 0.871005 9.993069\n4851 0.222131 -0.003946 -0.003084 -0.010174 0.761500 0.880217 9.977531\n4852 0.228254 -0.003879 -0.003474 -0.009756 0.765109 0.891078 9.981617\n4853 0.234211 -0.003555 -0.003447 -0.009907 0.771041 0.873861 9.992127\n4854 0.240293 -0.003625 -0.002568 -0.010761 0.772855 0.862627 10.013085\n4855 0.246236 -0.003801 -0.001943 -0.011092 0.770824 0.874135 10.016540\n4856 0.252405 -0.003938 -0.001253 -0.012078 0.769656 0.884538 10.010464\n4857 0.258485 -0.003875 -0.001337 -0.012236 0.766865 0.884404 10.012032\n4858 0.264636 -0.004348 -0.002036 -0.011465 0.763886 0.896699 10.019296\n4859 0.270534 -0.004501 -0.002489 -0.010991 0.767631 0.913950 10.018021\n4860 0.276631 -0.004316 -0.002559 -0.010561 0.773660 0.909678 10.004559\n4861 0.282383 -0.003904 -0.002093 -0.010622 0.780466 0.894855 10.001389\n4862 0.288540 -0.003795 -0.001711 -0.011011 0.787094 0.907603 9.990109\n4863 0.294614 -0.003626 -0.001883 -0.011169 0.782690 0.915804 9.984503\n4864 0.300595 -0.003535 -0.001427 -0.011334 0.771185 0.894589 9.989120\n4865 0.306612 -0.003882 -0.001476 -0.011090 0.757615 0.877664 9.997867\n4866 0.312581 -0.004181 -0.002240 -0.010537 0.738805 0.862826 10.004238\n4867 0.318917 -0.004130 -0.002772 -0.010577 0.740163 0.868548 9.997676\n4868 0.324830 -0.003847 -0.003207 -0.010586 0.754676 0.878098 9.993180\n4869 0.330918 -0.003469 -0.003286 -0.010790 0.754153 0.885173 10.004667\n4870 0.336921 -0.002883 -0.001905 -0.010979 0.747985 0.905043 10.002390\n4871 0.342925 -0.002901 -0.001498 -0.010935 0.757079 0.907220 9.998121\n4872 0.348913 -0.002949 -0.001995 -0.011362 0.780396 0.874923 9.985785\n4873 0.354923 -0.003014 -0.002089 -0.011506 0.777453 0.869042 9.988387\n4874 0.361169 -0.002649 -0.002276 -0.010737 0.771829 0.894818 9.980692\n4875 0.367041 -0.002471 -0.002439 -0.010035 0.769496 0.903341 9.975252\n4876 0.373144 -0.003087 -0.001935 -0.009977 0.765712 0.890994 10.000338\n4877 0.379100 -0.003853 -0.001891 -0.010250 0.765096 0.895559 10.013384\n4878 0.385224 -0.003950 -0.001557 -0.011096 0.751606 0.904691 9.997955\n4879 0.391256 -0.003208 -0.001474 -0.011342 0.753995 0.892351 9.983452\n4880 0.397121 -0.002994 -0.001604 -0.011544 0.766521 0.868543 9.987408\n4881 0.403730 -0.003597 -0.001628 -0.011368 0.768834 0.870007 10.004652\n4882 0.409318 -0.003753 -0.002215 -0.010796 0.754402 0.882936 10.015345\n4883 0.415892 -0.003760 -0.002884 -0.010836 0.751077 0.883860 10.000188\n4884 0.421415 -0.003799 -0.002576 -0.011174 0.754403 0.893250 9.997902\n4885 0.427874 -0.003468 -0.002080 -0.011774 0.746287 0.922800 9.996577\n4886 0.433571 -0.003755 -0.001692 -0.011853 0.741555 0.925306 9.992783\n4887 0.439940 -0.004384 -0.001834 -0.011706 0.745314 0.889180 9.988578\n4888 0.445582 -0.004637 -0.002052 -0.011308 0.755479 0.884826 9.993653\n4889 0.452009 -0.003795 -0.003267 -0.010485 0.757493 0.906326 10.011084\n4890 0.457714 -0.003835 -0.003604 -0.010528 0.766687 0.903822 10.025890\n4891 0.464191 -0.003894 -0.003271 -0.010692 0.783248 0.895210 10.032934\n4892 0.469734 -0.003535 -0.002825 -0.010845 0.781013 0.900871 10.026121\n4893 0.476012 -0.003011 -0.001795 -0.011101 0.766643 0.900122 10.017224\n4894 0.481887 -0.003157 -0.001686 -0.010943 0.763799 0.892065 10.009028\n4895 0.487950 -0.003771 -0.001315 -0.010911 0.763455 0.867745 10.009565\n4896 0.494127 -0.003770 -0.001367 -0.010658 0.768898 0.873368 10.010985\n4897 0.500110 -0.003021 -0.001327 -0.010075 0.779217 0.882380 10.006041\n4898 0.505968 -0.002557 -0.001456 -0.010213 0.774180 0.884828 10.013267\n4899 0.512191 -0.002823 -0.001917 -0.010528 0.755303 0.900008 10.013344\n4900 0.517917 -0.003364 -0.002109 -0.010766 0.748062 0.907719 9.998503\n4901 0.524180 -0.003473 -0.002089 -0.011287 0.744307 0.881210 9.994876\n4902 0.530034 -0.003485 -0.002211 -0.011052 0.750422 0.857963 9.999709\n4903 0.536215 -0.003273 -0.002314 -0.010449 0.766956 0.868631 9.993167\n4904 0.542078 -0.003180 -0.002131 -0.010308 0.773190 0.884310 10.004499\n4905 0.548371 -0.002982 -0.002147 -0.010451 0.764731 0.886822 10.037585\n4906 0.554242 -0.003180 -0.002127 -0.010632 0.753543 0.883539 10.036097\n4907 0.560628 -0.004232 -0.001637 -0.011052 0.749062 0.894693 10.013830\n4908 0.566265 -0.004630 -0.001840 -0.011354 0.745793 0.904933 10.006979\n4909 0.572343 -0.004121 -0.002327 -0.011637 0.750071 0.884259 10.002224\n4910 0.578311 -0.003805 -0.002656 -0.011558 0.754590 0.868764 9.998874\n4911 0.584447 -0.003121 -0.003092 -0.011018 0.772070 0.872309 10.000736\n4912 0.590495 -0.002580 -0.003207 -0.010691 0.773948 0.873882 10.002404\n4913 0.596560 -0.002079 -0.003021 -0.010097 0.771955 0.862824 10.009992\n4914 0.602664 -0.002145 -0.002579 -0.010226 0.765002 0.870941 10.003470\n4915 0.608605 -0.002889 -0.002104 -0.011092 0.752365 0.898487 9.988558\n4916 0.614737 -0.002765 -0.001732 -0.011603 0.758914 0.899520 9.994972\n4917 0.620737 -0.002822 -0.000872 -0.011654 0.771467 0.876749 9.998906\n4918 0.626959 -0.003182 -0.000902 -0.010981 0.776741 0.873573 9.994737\n4919 0.632831 -0.003210 -0.001338 -0.010081 0.779767 0.900296 10.009242\n4920 0.638799 -0.003103 -0.001845 -0.009960 0.770176 0.906136 10.020245\n4921 0.644989 -0.003071 -0.002504 -0.009695 0.738602 0.890267 10.021225\n4922 0.650873 -0.003293 -0.002619 -0.010001 0.732247 0.892507 10.012517\n4923 0.657060 -0.003917 -0.001815 -0.011325 0.727529 0.901326 10.001326\n4924 0.663023 -0.003872 -0.001672 -0.011529 0.730884 0.893301 10.000812\n4925 0.669227 -0.003617 -0.002175 -0.011676 0.760844 0.870751 9.998134\n4926 0.674962 -0.003408 -0.002717 -0.011700 0.769610 0.871427 10.003327\n4927 0.681194 -0.002892 -0.003296 -0.011088 0.768797 0.894475 10.026628\n4928 0.687112 -0.003174 -0.002766 -0.010383 0.763832 0.890053 10.033661\n4929 0.693303 -0.003684 -0.001797 -0.010537 0.764596 0.891154 10.022697\n4930 0.699252 -0.004092 -0.001349 -0.010818 0.767235 0.909277 10.025023\n4931 0.705262 -0.003860 -0.002015 -0.010878 0.772484 0.912176 10.032144\n4932 0.711254 -0.003840 -0.002242 -0.011011 0.769593 0.892252 10.033835\n4933 0.717363 -0.004438 -0.001967 -0.010828 0.757678 0.863768 10.014419\n4934 0.723382 -0.004747 -0.002070 -0.010849 0.753305 0.864093 10.007121\n4935 0.729590 -0.004076 -0.002865 -0.010468 0.765705 0.866593 9.988792\n4936 0.735563 -0.003677 -0.002914 -0.010145 0.764399 0.860688 9.985010\n4937 0.741443 -0.003337 -0.002435 -0.010325 0.743652 0.872919 9.992844\n4938 0.747494 -0.003443 -0.001519 -0.010586 0.743012 0.891620 10.008532\n4939 0.753557 -0.003265 -0.000965 -0.010856 0.760737 0.879845 10.029436\n4940 0.759751 -0.003666 -0.001042 -0.010820 0.767479 0.868308 10.024084\n4941 0.765690 -0.003781 -0.001545 -0.010944 0.770919 0.875087 10.013207\n4942 0.771755 -0.003529 -0.001954 -0.010589 0.765047 0.884249 10.009870\n4943 0.777936 -0.003366 -0.002403 -0.010075 0.752636 0.884164 10.001451\n4944 0.783856 -0.003459 -0.002238 -0.010159 0.755082 0.883717 10.002476\n4945 0.789939 -0.003764 -0.001577 -0.010501 0.752995 0.900367 10.007043\n4946 0.796353 -0.004218 -0.001317 -0.011091 0.755597 0.904810 10.009259\n4947 0.802023 -0.004512 -0.000992 -0.011828 0.765071 0.882976 10.007751\n4948 0.808575 -0.004154 -0.001136 -0.010883 0.767631 0.880055 9.998522\n4949 0.814110 -0.004126 -0.001623 -0.010552 0.761933 0.889651 10.004203\n4950 0.820415 -0.003789 -0.002969 -0.010325 0.765845 0.879996 10.015238\n4951 0.826259 -0.003560 -0.002904 -0.010190 0.766896 0.875190 10.015765\n4952 0.832642 -0.003740 -0.003018 -0.010463 0.758726 0.914766 9.998699\n4953 0.838235 -0.003622 -0.003018 -0.010881 0.757962 0.928314 9.988050\n4954 0.844644 -0.002989 -0.002200 -0.011406 0.774556 0.898459 9.970419\n4955 0.850270 -0.003359 -0.002081 -0.011425 0.785789 0.886799 9.968897\n4956 0.856610 -0.003773 -0.001921 -0.011329 0.777679 0.889713 9.970936\n4957 0.862395 -0.003486 -0.002343 -0.011068 0.772208 0.890824 9.978352\n4958 0.868635 -0.002344 -0.002580 -0.010384 0.769860 0.881772 9.997687\n4959 0.874379 -0.002466 -0.002678 -0.010340 0.770102 0.877640 10.003568\n4960 0.880614 -0.002929 -0.002167 -0.010690 0.758001 0.893708 10.003065\n4961 0.886483 -0.002995 -0.002070 -0.011068 0.747533 0.888443 10.000245\n4962 0.892887 -0.003395 -0.001601 -0.011149 0.745355 0.856113 9.998816\n4963 0.898778 -0.003732 -0.001386 -0.011037 0.761275 0.853380 10.002135\n4964 0.904608 -0.003753 -0.001308 -0.011050 0.774140 0.885712 10.013830\n4965 0.910781 -0.003372 -0.001809 -0.010896 0.771994 0.892893 10.014862\n4966 0.918933 -0.003508 -0.002854 -0.010440 0.773675 0.893847 10.012815\n4967 0.922898 -0.003699 -0.003148 -0.010508 0.769022 0.907947 9.995874\n4968 0.928781 -0.003175 -0.002411 -0.011317 0.761758 0.922161 9.975470\n4969 0.934789 -0.003267 -0.002067 -0.011642 0.767926 0.907563 9.986673\n4970 0.941108 -0.003486 -0.001937 -0.011540 0.777949 0.880434 9.986512\n4971 0.946848 -0.003493 -0.002111 -0.011060 0.772600 0.871930 9.983227\n4972 0.952960 -0.003776 -0.001988 -0.010017 0.758772 0.873354 10.005732\n4973 0.958942 -0.003757 -0.001824 -0.010185 0.756353 0.879397 10.011158\n4974 0.965141 -0.003863 -0.001896 -0.010615 0.751208 0.896548 9.993069\n4975 0.970978 -0.003627 -0.001459 -0.011336 0.748557 0.909821 9.996194\n4976 0.977337 -0.003130 -0.001023 -0.012342 0.742957 0.912004 10.010765\n4977 0.983154 -0.003302 -0.001087 -0.012165 0.736819 0.886379 10.007341\n4978 0.989190 -0.004137 -0.001389 -0.011434 0.737616 0.871603 9.999038\n4979 0.995168 -0.003770 -0.001397 -0.011216 0.739927 0.882741 10.001513\n4980 1.001215 -0.003050 -0.001321 -0.010641 0.753881 0.887605 10.005328\n4981 1.007241 -0.002908 -0.001535 -0.010542 0.761220 0.879396 10.003333\n4982 1.013270 -0.002963 -0.001861 -0.010553 0.764200 0.901304 9.997782\n4983 1.019409 -0.003227 -0.001469 -0.010665 0.764312 0.911590 9.990205\n4984 1.025590 -0.003399 -0.001240 -0.011443 0.769565 0.894291 9.976709\n4985 1.031623 -0.003750 -0.001596 -0.011754 0.767208 0.886156 9.968451\n4986 1.037564 -0.004214 -0.002582 -0.011617 0.762428 0.891837 9.983237\n4987 1.043675 -0.004058 -0.003055 -0.011322 0.766002 0.895770 9.998416\n4988 1.049609 -0.003092 -0.003454 -0.010340 0.765585 0.886821 10.008243\n4989 1.055564 -0.002957 -0.003480 -0.009922 0.758177 0.887650 10.005866\n4990 1.061518 -0.002880 -0.003262 -0.010367 0.746555 0.903882 10.007786\n4991 1.067679 -0.002650 -0.002880 -0.010948 0.751489 0.902151 10.015574\n4992 1.073832 -0.002786 -0.002064 -0.011695 0.756518 0.883986 10.016003\n4993 1.079776 -0.003107 -0.001944 -0.011825 0.758947 0.880737 10.026119\n4994 1.085843 -0.003431 -0.002326 -0.011320 0.760401 0.894141 10.019913\n4995 1.091804 -0.003450 -0.002108 -0.010980 0.764059 0.886058 10.007259\n4996 1.097955 -0.003352 -0.001992 -0.010437 0.765684 0.869828 9.986824\n4997 1.103887 -0.003349 -0.002032 -0.010400 0.761923 0.885414 9.978074\n4998 1.109943 -0.003157 -0.002246 -0.010628 0.744781 0.903479 9.980357\n4999 1.115950 -0.003055 -0.002304 -0.010980 0.737986 0.892267 9.995916\n5000 1.121990 -0.003805 -0.002303 -0.010898 0.740734 0.874331 10.006081\n5001 1.128131 -0.004099 -0.001999 -0.010739 0.748206 0.879751 10.002735\n5002 1.134079 -0.004253 -0.002202 -0.010238 0.762947 0.883629 10.001728\n5003 1.140255 -0.004368 -0.002649 -0.010137 0.763145 0.879701 10.010201\n5004 1.146266 -0.004253 -0.002610 -0.010132 0.763092 0.888524 10.024725\n5005 1.152414 -0.004244 -0.002333 -0.010426 0.760234 0.896520 10.020974\n5006 1.158340 -0.004079 -0.002009 -0.011340 0.757541 0.903577 10.013026\n5007 1.164340 -0.004113 -0.002587 -0.011638 0.757679 0.900372 10.016126\n5008 1.170330 -0.003879 -0.003323 -0.012000 0.771392 0.894929 10.019054\n5009 1.176385 -0.003909 -0.003428 -0.011809 0.773564 0.896568 10.018826\n5010 1.182426 -0.003772 -0.003020 -0.010955 0.762951 0.887999 10.013963\n5011 1.188499 -0.003752 -0.002679 -0.010697 0.764583 0.875258 10.011650\n5012 1.194784 -0.003734 -0.002113 -0.010542 0.758816 0.873393 9.997181\n5013 1.200618 -0.003435 -0.001779 -0.010591 0.753830 0.889321 9.996597\n5014 1.206788 -0.003434 -0.001312 -0.010994 0.769473 0.899784 9.994003\n5015 1.212669 -0.003932 -0.001396 -0.010947 0.773225 0.893232 9.983994\n5016 1.218678 -0.004951 -0.001605 -0.010677 0.768247 0.888434 9.973659\n5017 1.225213 -0.004148 -0.001771 -0.010762 0.756471 0.891250 9.978215\n5018 1.230930 -0.003710 -0.002039 -0.010744 0.757705 0.889067 9.987072\n5019 1.237413 -0.003740 -0.002235 -0.010652 0.760358 0.890274 9.986737\n5020 1.243045 -0.003686 -0.002301 -0.010596 0.764798 0.898853 9.987735\n5021 1.249457 -0.003503 -0.001570 -0.010882 0.763260 0.914468 9.993475\n5022 1.254976 -0.003687 -0.001292 -0.011194 0.761744 0.894105 9.994718\n5023 1.261485 -0.004164 -0.002483 -0.011624 0.756745 0.884505 9.998736\n5024 1.267077 -0.003712 -0.003123 -0.011508 0.747995 0.891939 9.992647\n5025 1.273381 -0.003664 -0.003702 -0.010511 0.748651 0.882660 9.993752\n5026 1.279143 -0.004104 -0.003868 -0.010286 0.753060 0.869827 10.000538\n5027 1.285312 -0.003938 -0.003004 -0.010687 0.751287 0.876091 10.007535\n5028 1.291333 -0.003263 -0.002585 -0.011165 0.750730 0.887815 10.013043\n5029 1.297451 -0.002946 -0.002187 -0.011411 0.751495 0.879106 10.008453\n5030 1.303329 -0.003069 -0.002524 -0.011463 0.752102 0.877420 10.002646\n5031 1.309431 -0.003142 -0.002448 -0.010932 0.755834 0.890503 10.010941\n5032 1.315555 -0.003089 -0.002465 -0.010620 0.749772 0.891344 10.019573\n5033 1.321595 -0.002957 -0.001792 -0.010182 0.748746 0.876672 10.014710\n5034 1.327589 -0.003073 -0.001437 -0.010298 0.747009 0.874267 10.001152\n5035 1.333679 -0.002928 -0.001446 -0.010557 0.753395 0.891055 9.978673\n5036 1.339671 -0.002750 -0.001454 -0.010819 0.757061 0.890664 9.982361\n5037 1.345670 -0.002582 -0.001431 -0.010962 0.775263 0.872525 10.002674\n5038 1.351624 -0.003074 -0.001965 -0.011268 0.770476 0.866087 10.004939\n5039 1.357792 -0.003665 -0.003057 -0.011011 0.755438 0.878978 10.003308\n5040 1.363802 -0.003654 -0.003114 -0.010898 0.759114 0.883682 9.997901\n5041 1.369778 -0.003097 -0.003131 -0.010813 0.759519 0.870351 9.981132\n5042 1.375746 -0.003164 -0.003253 -0.010507 0.757769 0.872277 9.987530\n5043 1.381804 -0.003649 -0.003350 -0.010616 0.760353 0.888184 9.996992\n5044 1.387994 -0.003485 -0.003068 -0.010429 0.761639 0.890953 9.997165\n5045 1.394009 -0.003489 -0.002392 -0.010912 0.751564 0.888793 9.995048\n5046 1.400049 -0.003710 -0.002500 -0.011001 0.744772 0.889837 9.988647\n5047 1.406034 -0.003977 -0.002777 -0.010995 0.750991 0.898184 9.987047\n5048 1.411963 -0.003804 -0.002744 -0.010807 0.756081 0.893003 9.982361\n5049 1.418102 -0.002712 -0.002768 -0.010621 0.756414 0.896814 9.992275\n5050 1.424265 -0.002711 -0.002750 -0.010835 0.750402 0.913002 10.010714\n5051 1.430104 -0.003126 -0.002404 -0.011116 0.757557 0.920485 10.035940\n5052 1.436235 -0.003166 -0.002144 -0.011156 0.762690 0.901116 10.034170\n5053 1.442281 -0.003666 -0.002206 -0.011258 0.761288 0.882740 10.017912\n5054 1.448439 -0.004090 -0.002298 -0.011009 0.754070 0.889312 10.017257\n5055 1.454311 -0.004083 -0.002781 -0.010598 0.750526 0.887788 10.022785\n5056 1.460404 -0.003460 -0.002648 -0.010506 0.753826 0.883292 10.029387\n5057 1.466390 -0.003003 -0.001388 -0.010521 0.758495 0.895278 10.029047\n5058 1.472421 -0.003377 -0.001213 -0.010931 0.765990 0.902919 10.025358\n5059 1.478538 -0.003602 -0.001910 -0.011478 0.774743 0.889629 10.031688\n5060 1.484577 -0.003767 -0.002060 -0.011303 0.772533 0.877087 10.036618\n5061 1.490690 -0.003984 -0.002320 -0.011471 0.761735 0.879695 10.026274\n5062 1.496501 -0.004218 -0.002397 -0.011099 0.760303 0.882393 10.014932\n5063 1.502753 -0.003949 -0.002788 -0.010991 0.780972 0.873498 10.011477\n5064 1.508585 -0.003528 -0.002870 -0.011148 0.780998 0.868579 10.022425\n5065 1.514745 -0.003146 -0.002587 -0.011079 0.774424 0.899418 10.008588\n5066 1.520662 -0.003246 -0.002275 -0.011075 0.773561 0.912378 9.992481\n5067 1.526845 -0.003364 -0.001751 -0.011125 0.783508 0.901727 9.974930\n5068 1.532889 -0.003879 -0.001857 -0.010853 0.783746 0.893661 9.980748\n5069 1.538841 -0.004065 -0.002779 -0.010463 0.772373 0.894454 9.999691\n5070 1.544981 -0.003719 -0.003010 -0.010390 0.768806 0.884413 10.003330\n5071 1.550963 -0.003519 -0.002990 -0.010512 0.749932 0.859029 10.030059\n5072 1.557952 -0.003587 -0.002725 -0.010568 0.742415 0.871155 10.041631\n5073 1.563184 -0.003666 -0.002293 -0.010581 0.746517 0.904344 10.035887\n5074 1.569260 -0.003702 -0.001953 -0.010519 0.754135 0.910441 10.038750\n5075 1.575248 -0.004084 -0.001485 -0.011025 0.761278 0.904542 10.041262\n5076 1.581252 -0.004097 -0.001476 -0.011218 0.764110 0.900322 10.025136\n5077 1.587317 -0.003503 -0.001770 -0.010809 0.767726 0.883000 9.997203\n5078 1.593975 -0.003067 -0.002124 -0.009910 0.760871 0.859263 9.990005\n5079 1.599384 -0.003520 -0.002208 -0.009633 0.762824 0.860497 9.978555\n5080 1.605884 -0.003773 -0.002568 -0.009873 0.761305 0.894334 9.975914\n5081 1.611618 -0.003756 -0.002695 -0.010079 0.762264 0.904983 9.987282\n5082 1.618038 -0.003905 -0.002694 -0.010509 0.759855 0.890156 10.008797\n5083 1.623615 -0.004003 -0.002545 -0.010838 0.760724 0.884948 10.003339\n5084 1.630003 -0.004001 -0.002340 -0.011382 0.769964 0.901526 9.999043\n5085 1.635649 -0.003871 -0.002305 -0.011011 0.773497 0.902119 10.001685\n5086 1.642154 -0.003785 -0.001809 -0.010135 0.772415 0.878259 10.003898\n5087 1.647615 -0.003494 -0.001877 -0.010168 0.764029 0.884257 10.005466\n5088 1.654139 -0.003012 -0.002294 -0.010259 0.748273 0.907296 10.013286\n5089 1.659919 -0.003039 -0.002424 -0.010781 0.753018 0.905982 10.012410\n5090 1.666171 -0.003479 -0.002102 -0.011557 0.763317 0.888875 9.999671\n5091 1.671716 -0.003451 -0.001897 -0.011698 0.774457 0.888686 9.994031\n5092 1.678124 -0.003305 -0.002590 -0.011397 0.767785 0.886081 9.991673\n5093 1.684003 -0.003433 -0.002921 -0.011029 0.761317 0.872386 9.993619\n5094 1.690221 -0.004104 -0.002479 -0.010432 0.755036 0.868118 9.991058\n5095 1.695975 -0.003944 -0.002368 -0.010430 0.754029 0.883420 10.000881\n5096 1.702239 -0.003571 -0.002193 -0.011034 0.766163 0.905090 10.009409\n5097 1.708189 -0.003557 -0.002137 -0.010900 0.770656 0.895972 10.008327\n5098 1.714153 -0.004626 -0.003232 -0.010648 0.773495 0.888898 9.995463\n5099 1.720138 -0.004920 -0.003744 -0.010687 0.766989 0.889927 9.987671\n5100 1.726282 -0.004562 -0.003363 -0.010739 0.766286 0.880991 9.994721\n5101 1.732300 -0.004413 -0.002872 -0.010680 0.765150 0.871993 9.994686\n5102 1.738295 -0.004579 -0.002761 -0.010684 0.747379 0.888977 9.995470\n5103 1.744454 -0.004499 -0.002821 -0.010502 0.743572 0.897157 10.000750\n5104 1.750427 -0.004371 -0.002705 -0.010323 0.761271 0.889280 10.013372\n5105 1.756607 -0.004424 -0.002449 -0.010257 0.767662 0.884320 10.011659\n5106 1.762414 -0.004067 -0.001934 -0.010804 0.761312 0.895211 9.999824\n5107 1.768481 -0.003808 -0.001641 -0.011226 0.753232 0.891701 9.995673\n5108 1.774644 -0.003616 -0.001839 -0.011404 0.756209 0.876143 9.996067\n5109 1.780671 -0.003445 -0.002081 -0.011171 0.757346 0.877085 10.003193\n5110 1.786872 -0.002944 -0.002861 -0.010782 0.752109 0.896949 10.000203\n5111 1.792672 -0.002857 -0.003124 -0.010722 0.752300 0.902044 9.999887\n5112 1.798791 -0.003393 -0.002501 -0.010620 0.763498 0.890631 10.013667\n5113 1.804725 -0.003722 -0.002575 -0.010602 0.773216 0.891451 10.019251\n5114 1.810788 -0.004187 -0.002356 -0.010430 0.778004 0.895946 10.013196\n5115 1.816774 -0.003760 -0.002491 -0.010331 0.772300 0.885350 10.014172\n5116 1.822891 -0.003360 -0.002356 -0.010826 0.768948 0.868114 10.012780\n5117 1.828949 -0.003744 -0.002273 -0.011239 0.765187 0.870732 10.012465\n5118 1.834856 -0.003859 -0.001878 -0.011628 0.763213 0.897597 10.008261\n5119 1.840943 -0.003961 -0.002407 -0.011605 0.767624 0.897105 9.999316\n5120 1.846961 -0.004737 -0.003082 -0.011272 0.776415 0.889790 10.005678\n5121 1.853137 -0.004444 -0.003057 -0.010916 0.775711 0.895036 10.016517\n5122 1.859027 -0.003996 -0.002323 -0.010602 0.775257 0.897333 9.999325\n5123 1.865137 -0.004249 -0.002468 -0.010562 0.771481 0.891082 9.985546\n5124 1.871162 -0.004628 -0.002626 -0.010731 0.754055 0.873947 9.978256\n5125 1.877268 -0.004261 -0.002546 -0.011130 0.751107 0.882498 9.986624\n5126 1.883182 -0.003351 -0.002189 -0.011636 0.756603 0.893774 10.003366\n5127 1.889217 -0.003594 -0.002022 -0.011704 0.762984 0.878330 10.002949\n5128 1.895396 -0.003924 -0.002644 -0.011708 0.759103 0.869515 9.997422\n5129 1.901275 -0.003798 -0.002716 -0.011694 0.755763 0.881346 9.996299\n5130 1.907429 -0.004092 -0.002336 -0.011109 0.747468 0.883611 9.995202\n5131 1.913516 -0.004124 -0.002185 -0.010702 0.754627 0.879395 9.992607\n5132 1.919514 -0.003826 -0.001583 -0.010076 0.757332 0.892423 10.000697\n5133 1.925519 -0.003093 -0.001561 -0.010209 0.758265 0.909996 10.008656\n5134 1.931609 -0.002878 -0.001996 -0.010656 0.765131 0.905465 10.014567\n5135 1.937572 -0.003508 -0.001934 -0.010940 0.774875 0.893075 10.003377\n5136 1.943611 -0.003733 -0.002314 -0.011518 0.776386 0.895974 9.980772\n5137 1.949639 -0.003237 -0.002449 -0.011495 0.772709 0.899673 9.979362\n5138 1.955839 -0.003467 -0.002373 -0.010889 0.757431 0.878743 9.992220\n5139 1.961873 -0.004095 -0.002107 -0.010613 0.751739 0.875542 9.993282\n5140 1.967744 -0.004546 -0.002044 -0.011089 0.753623 0.898300 9.983396\n5141 1.973859 -0.004151 -0.002064 -0.011366 0.761606 0.906000 9.984287\n5142 1.979899 -0.003989 -0.002077 -0.010953 0.769325 0.891903 10.006207\n5143 1.985956 -0.004018 -0.002019 -0.011020 0.767062 0.888132 10.016363\n5144 1.992015 -0.004413 -0.002021 -0.011207 0.760766 0.900827 10.021577\n5145 1.998057 -0.003980 -0.002393 -0.011329 0.758426 0.898791 10.004894\n5146 2.004082 -0.003681 -0.002633 -0.010896 0.759215 0.873751 9.994824\n5147 2.009918 -0.003632 -0.002749 -0.010518 0.756432 0.867683 9.995871\n5148 2.016051 -0.004030 -0.002278 -0.010791 0.764740 0.875173 9.999340\n5149 2.022195 -0.004010 -0.002046 -0.010672 0.763946 0.876073 10.001344\n5150 2.028298 -0.003387 -0.001560 -0.010724 0.765391 0.871077 9.996834\n5151 2.034199 -0.003317 -0.001616 -0.010792 0.764962 0.889355 9.987096\n5152 2.040389 -0.003637 -0.002114 -0.010914 0.756176 0.919456 9.968994\n5153 2.046190 -0.003664 -0.002278 -0.010808 0.754884 0.913696 9.971729\n5154 2.052331 -0.003428 -0.002880 -0.010551 0.755417 0.892808 9.987762\n5155 2.058817 -0.003441 -0.002776 -0.010345 0.755162 0.896461 9.995975\n5156 2.064383 -0.003453 -0.002078 -0.010608 0.757676 0.892599 10.010681\n5157 2.070832 -0.004314 -0.001674 -0.010249 0.773669 0.868618 10.010301\n5158 2.076585 -0.004594 -0.001658 -0.010129 0.780075 0.870800 10.009805\n5159 2.083042 -0.004151 -0.001610 -0.009955 0.774242 0.899063 10.005130\n5160 2.088705 -0.003680 -0.001488 -0.010163 0.766693 0.894543 9.999719\n5161 2.094918 -0.003799 -0.001806 -0.010881 0.762554 0.879748 10.001287\n5162 2.100641 -0.003895 -0.001960 -0.010912 0.765114 0.878475 9.997455\n5163 2.107152 -0.003229 -0.001763 -0.010658 0.768984 0.877893 9.998165\n5164 2.112758 -0.002976 -0.001799 -0.010277 0.770063 0.884161 10.001782\n5165 2.119156 -0.003852 -0.001764 -0.010116 0.780475 0.894082 10.001206\n5166 2.124852 -0.004383 -0.002182 -0.010447 0.779300 0.901924 10.000212\n5167 2.130910 -0.003905 -0.003171 -0.011435 0.778573 0.899455 9.996961\n5168 2.136731 -0.003748 -0.003106 -0.011768 0.780204 0.887100 10.002902\n5169 2.143104 -0.003193 -0.002201 -0.011161 0.781172 0.867820 10.004873\n5170 2.149015 -0.003047 -0.002035 -0.010916 0.774392 0.875844 10.002477\n5171 2.155041 -0.003107 -0.002175 -0.010463 0.743486 0.886224 9.986968\n5172 2.161070 -0.003133 -0.002178 -0.010246 0.744552 0.884661 9.985361\n5173 2.167183 -0.003315 -0.002319 -0.010412 0.765920 0.905361 9.990523\n5174 2.173033 -0.003125 -0.002469 -0.010527 0.770342 0.922727 9.990995\n5175 2.179129 -0.002754 -0.002419 -0.010964 0.768375 0.908957 9.988420\n5176 2.185111 -0.002740 -0.002074 -0.011070 0.766466 0.890526 9.990575\n5177 2.191353 -0.003226 -0.001840 -0.011060 0.758287 0.889249 10.005196\n5178 2.197203 -0.003374 -0.002121 -0.010910 0.761469 0.889248 10.018480\n5179 2.203406 -0.003582 -0.002538 -0.010388 0.764932 0.878495 10.020984\n5180 2.209416 -0.003549 -0.002456 -0.010376 0.765867 0.884837 10.022295\n5181 2.215343 -0.002928 -0.002549 -0.010588 0.750557 0.902742 10.024081\n5182 2.221567 -0.002941 -0.002920 -0.010707 0.755222 0.906318 10.018065\n5183 2.227585 -0.003755 -0.002757 -0.011279 0.766737 0.894039 9.990361\n5184 2.233564 -0.004114 -0.002447 -0.011347 0.765494 0.892770 9.974909\n5185 2.239592 -0.003709 -0.001692 -0.010870 0.771467 0.901159 9.984106\n5186 2.245634 -0.003644 -0.001734 -0.010653 0.776356 0.902042 9.996031\n5187 2.251575 -0.003754 -0.002497 -0.010268 0.781879 0.884831 10.013168\n5188 2.257645 -0.003871 -0.002968 -0.010667 0.776324 0.886432 10.007022\n5189 2.263703 -0.003742 -0.003286 -0.011055 0.770259 0.898506 10.008340\n5190 2.269845 -0.003459 -0.003159 -0.011325 0.760671 0.894218 10.010889\n5191 2.275790 -0.003397 -0.002244 -0.011633 0.756597 0.876452 9.995905\n5192 2.281912 -0.003876 -0.001714 -0.011313 0.763474 0.878597 9.987525\n5193 2.287938 -0.004569 -0.001393 -0.010967 0.771054 0.879780 9.972951\n5194 2.294003 -0.004697 -0.001717 -0.010774 0.776354 0.867491 9.992999\n5195 2.299925 -0.004397 -0.002678 -0.010588 0.782033 0.865096 10.012915\n5196 2.305991 -0.003771 -0.002802 -0.010311 0.777122 0.882855 10.014747\n5197 2.312125 -0.003284 -0.002880 -0.010588 0.770160 0.896092 10.019094\n5198 2.318122 -0.003319 -0.002656 -0.011012 0.768456 0.891267 10.018088\n5199 2.324207 -0.002964 -0.002309 -0.011603 0.764307 0.886107 10.018806\n5200 2.330131 -0.003115 -0.001832 -0.011547 0.766503 0.888052 10.020192\n5201 2.336212 -0.003459 -0.001113 -0.011579 0.778838 0.883744 10.016171\n5202 2.342311 -0.003331 -0.001545 -0.011532 0.779970 0.877963 10.016259\n5203 2.348373 -0.003356 -0.002455 -0.011077 0.761217 0.904942 10.007701\n5204 2.354541 -0.003628 -0.002721 -0.011041 0.751975 0.921389 9.997465\n5205 2.360433 -0.003684 -0.002922 -0.010677 0.745118 0.905152 9.974667\n5206 2.366497 -0.003541 -0.002700 -0.010516 0.745709 0.887409 9.979288\n5207 2.372514 -0.003088 -0.002600 -0.010865 0.758230 0.899208 9.974474\n5208 2.378555 -0.003170 -0.002347 -0.010937 0.768031 0.907009 9.974478\n5209 2.384533 -0.003093 -0.001857 -0.011137 0.764587 0.896767 9.998222\n5210 2.390634 -0.003014 -0.001891 -0.011334 0.754769 0.892327 10.001895\n5211 2.396521 -0.003054 -0.001843 -0.011274 0.738123 0.899905 9.998278\n5212 2.402770 -0.003288 -0.002017 -0.011056 0.741381 0.900963 10.000043\n5213 2.408687 -0.003828 -0.002121 -0.010671 0.755278 0.873825 10.000343\n5214 2.414811 -0.003811 -0.001817 -0.010591 0.756532 0.869330 10.002517\n5215 2.420885 -0.003864 -0.001561 -0.010563 0.757944 0.878920 10.008938\n5216 2.426914 -0.003705 -0.001700 -0.010578 0.762439 0.883196 10.016397\n5217 2.432938 -0.003776 -0.002291 -0.010356 0.774969 0.869509 9.999775\n5218 2.438892 -0.003560 -0.002334 -0.010251 0.776430 0.874846 9.988470\n5219 2.445054 -0.003232 -0.002297 -0.010981 0.767497 0.917486 9.974088\n5220 2.451623 -0.003972 -0.002060 -0.011076 0.753595 0.906862 9.975070\n5221 2.457070 -0.004190 -0.002445 -0.010876 0.749639 0.886656 9.988867\n5222 2.463576 -0.003917 -0.002517 -0.010966 0.746275 0.880065 9.997839\n5223 2.469051 -0.003997 -0.002435 -0.011271 0.748335 0.872675 10.005498\n5224 2.475724 -0.003965 -0.002157 -0.011298 0.756027 0.861624 10.010324\n5225 2.481296 -0.003968 -0.002164 -0.010837 0.759876 0.865420 10.009739\n5226 2.487772 -0.003849 -0.002447 -0.010331 0.765013 0.895145 10.004911\n5227 2.493408 -0.003763 -0.002172 -0.010390 0.768220 0.901973 10.000383\n5228 2.499746 -0.003917 -0.001740 -0.010810 0.769245 0.878341 9.983610\n5229 2.505370 -0.004378 -0.002093 -0.010861 0.767691 0.871117 9.973390\n5230 2.511750 -0.004621 -0.002739 -0.010986 0.768499 0.894652 9.981950\n5231 2.517604 -0.004228 -0.002530 -0.010793 0.776421 0.895899 9.997129\n5232 2.523672 -0.004051 -0.002609 -0.010424 0.765761 0.883579 10.006834\n5233 2.529603 -0.004033 -0.002686 -0.010460 0.761485 0.887326 10.002779\n5234 2.535791 -0.003646 -0.002469 -0.010915 0.758727 0.914203 9.987355\n5235 2.541652 -0.003693 -0.002241 -0.011213 0.762111 0.911986 9.983917\n5236 2.547670 -0.004009 -0.001420 -0.011321 0.766686 0.896929 9.997595\n5237 2.553696 -0.004245 -0.001434 -0.011443 0.766980 0.892775 10.012929\n5238 2.559721 -0.004067 -0.002082 -0.011289 0.759965 0.888194 10.009165\n5239 2.565861 -0.003732 -0.002603 -0.010768 0.764247 0.870434 10.011478\n5240 2.571737 -0.003413 -0.002705 -0.009770 0.774544 0.876030 10.026319\n5241 2.577923 -0.003266 -0.002828 -0.009852 0.774872 0.892592 10.030782\n5242 2.583880 -0.003687 -0.003010 -0.010808 0.764855 0.913245 10.009047\n5243 2.590059 -0.003914 -0.002948 -0.011013 0.764333 0.907263 10.004154\n5244 2.595985 -0.004697 -0.002418 -0.010888 0.773415 0.878255 10.004870\n5245 2.601961 -0.004757 -0.002304 -0.010747 0.772458 0.871266 9.997669\n5246 2.608267 -0.003873 -0.001911 -0.011035 0.762790 0.875331 9.992394\n5247 2.614110 -0.003787 -0.001654 -0.010936 0.765823 0.882890 9.987976\n5248 2.620394 -0.003523 -0.001749 -0.010509 0.758834 0.899470 9.979247\n5249 2.626217 -0.003159 -0.001863 -0.010135 0.754032 0.910496 9.974113\n5250 2.632249 -0.003039 -0.002133 -0.010182 0.755444 0.909015 9.967340\n5251 2.638174 -0.003424 -0.002034 -0.010448 0.759736 0.896474 9.979113\n5252 2.644341 -0.004088 -0.001492 -0.011419 0.755858 0.892321 9.991449\n5253 2.650365 -0.004119 -0.001330 -0.011481 0.753395 0.898142 9.998311\n5254 2.656430 -0.003718 -0.001392 -0.010753 0.765844 0.880975 10.000576\n5255 2.662760 -0.003821 -0.001896 -0.010520 0.763531 0.873956 10.002997\n5256 2.668490 -0.003988 -0.002280 -0.009914 0.766065 0.905272 10.026777\n5257 2.674656 -0.003847 -0.002208 -0.010058 0.765908 0.908775 10.032296\n5258 2.680480 -0.003829 -0.002259 -0.010982 0.768284 0.891999 10.014305\n5259 2.686718 -0.004053 -0.002293 -0.011194 0.769447 0.893429 10.002413\n5260 2.692730 -0.004074 -0.002059 -0.011324 0.772593 0.898966 10.001442\n5261 2.698668 -0.003722 -0.002092 -0.011048 0.770115 0.884286 10.009490\n5262 2.704742 -0.003565 -0.002843 -0.010272 0.761982 0.859750 10.015505\n5263 2.710785 -0.004031 -0.003053 -0.010214 0.758389 0.873814 10.015441\n5264 2.716885 -0.003758 -0.003105 -0.010467 0.749644 0.913889 10.015860\n5265 2.722814 -0.003705 -0.003036 -0.010504 0.753177 0.911224 10.018273\n5266 2.728875 -0.004285 -0.002395 -0.010613 0.765846 0.901215 10.019444\n5267 2.734954 -0.004135 -0.002223 -0.011030 0.770502 0.903686 10.012437\n5268 2.740980 -0.003363 -0.002640 -0.010842 0.772856 0.890599 9.995930\n5269 2.747012 -0.003355 -0.002554 -0.010362 0.767509 0.879911 10.000440\n5270 2.753178 -0.003763 -0.002560 -0.009979 0.758492 0.875815 10.010077\n5271 2.759214 -0.003756 -0.002478 -0.009970 0.748217 0.889902 10.021502\n5272 2.765076 -0.003458 -0.002478 -0.010217 0.755592 0.910276 10.029200\n5273 2.771093 -0.003478 -0.002377 -0.010326 0.763348 0.905215 10.021065\n5274 2.777172 -0.003389 -0.001875 -0.010718 0.760925 0.898291 10.000571\n5275 2.783275 -0.003434 -0.001641 -0.010952 0.755817 0.902235 10.001242\n5276 2.789374 -0.004086 -0.001912 -0.010975 0.755246 0.891047 10.016500\n5277 2.795276 -0.004137 -0.002112 -0.010840 0.756621 0.879902 10.009497\n5278 2.801446 -0.004276 -0.002505 -0.010473 0.744831 0.875230 9.993909\n5279 2.807671 -0.003916 -0.002522 -0.010516 0.736619 0.894739 9.998411\n5280 2.813416 -0.003599 -0.002352 -0.011108 0.746202 0.899570 10.010634\n5281 2.819491 -0.004002 -0.002104 -0.011403 0.759631 0.887884 10.009583\n5282 2.825559 -0.004739 -0.002222 -0.011577 0.760089 0.890881 10.000767\n5283 2.831629 -0.004718 -0.002282 -0.011431 0.764535 0.892204 9.999678\n5284 2.837553 -0.003729 -0.001818 -0.011024 0.786418 0.885395 9.999557\n5285 2.843756 -0.003646 -0.001740 -0.010546 0.787350 0.885718 9.996066\n5286 2.849837 -0.003867 -0.001484 -0.009860 0.769739 0.902770 9.980723\n5287 2.856343 -0.003849 -0.001366 -0.009976 0.770072 0.907373 9.995152\n5288 2.862015 -0.003761 -0.001600 -0.010461 0.774232 0.891305 10.021166\n5289 2.868596 -0.004029 -0.000714 -0.011001 0.756324 0.895739 10.041629\n5290 2.873959 -0.004377 -0.000695 -0.011220 0.748436 0.911032 10.036884\n5291 2.880421 -0.004483 -0.001497 -0.011584 0.762456 0.899139 10.026930\n5292 2.886112 -0.004303 -0.001827 -0.011492 0.772888 0.880046 10.019371\n5293 2.892556 -0.004288 -0.002572 -0.010854 0.766529 0.886910 10.012958\n5294 2.898082 -0.004038 -0.003013 -0.010530 0.750633 0.896597 10.016520\n5295 2.904622 -0.003638 -0.002997 -0.010714 0.737008 0.894787 10.009540\n5296 2.910167 -0.004018 -0.002594 -0.010697 0.745881 0.892731 10.005905\n5297 2.916669 -0.004160 -0.002368 -0.010635 0.780122 0.899510 9.987115\n5298 2.922211 -0.004338 -0.002596 -0.010858 0.782876 0.892614 9.987015\n5299 2.928730 -0.004881 -0.002863 -0.011304 0.762059 0.872373 9.992555\n5300 2.934334 -0.004812 -0.002763 -0.010936 0.756514 0.872714 10.000229\n5301 2.940575 -0.004537 -0.002334 -0.010204 0.744101 0.890642 10.006175\n5302 2.946330 -0.003933 -0.002193 -0.010290 0.735504 0.897589 10.009610\n5303 2.952752 -0.002917 -0.001976 -0.011142 0.730484 0.898509 10.007604\n5304 2.958578 -0.002954 -0.001832 -0.011479 0.736128 0.893993 9.993822\n5305 2.964560 -0.003237 -0.002140 -0.012005 0.747994 0.891884 9.997540\n5306 2.970697 -0.003178 -0.002473 -0.012157 0.755317 0.882396 9.994920\n5307 2.976764 -0.002873 -0.002681 -0.011690 0.763929 0.869096 9.993753\n5308 2.982806 -0.002968 -0.002387 -0.010901 0.765873 0.877374 10.004613\n5309 2.988806 -0.003104 -0.002518 -0.009720 0.758200 0.896813 10.002033\n5310 2.994805 -0.002972 -0.002515 -0.009668 0.756124 0.890866 9.989016\n5311 3.000974 -0.003231 -0.002052 -0.010283 0.754939 0.874451 9.989381\n5312 3.006920 -0.003197 -0.001974 -0.010985 0.753572 0.880457 9.986626\n5313 3.013038 -0.003623 -0.001686 -0.011556 0.760700 0.879925 10.011058\n5314 3.019007 -0.004018 -0.001967 -0.011348 0.766993 0.873889 10.020638\n5315 3.025169 -0.003969 -0.003009 -0.010688 0.775930 0.874721 10.025877\n5316 3.030916 -0.003753 -0.003309 -0.010251 0.774607 0.880912 10.017518\n5317 3.037133 -0.003985 -0.003302 -0.010444 0.764181 0.898616 9.983351\n5318 3.043166 -0.004259 -0.002890 -0.010745 0.761633 0.898155 9.979529\n5319 3.049173 -0.003824 -0.001760 -0.011536 0.752880 0.902664 9.997816\n5320 3.055133 -0.003746 -0.001793 -0.011477 0.750151 0.901566 10.007264\n5321 3.061118 -0.003824 -0.001808 -0.011549 0.754168 0.877371 10.012782\n5322 3.067278 -0.003476 -0.002108 -0.011362 0.763044 0.856850 10.008896\n5323 3.073265 -0.002769 -0.002979 -0.010510 0.770989 0.860638 10.003159\n5324 3.079359 -0.003086 -0.003222 -0.010465 0.767611 0.870383 10.003249\n5325 3.085403 -0.003895 -0.003077 -0.010370 0.766170 0.890720 10.002429\n5326 3.091919 -0.004362 -0.002384 -0.010498 0.760304 0.895405 9.997927\n5327 3.097563 -0.003815 -0.001381 -0.011345 0.761244 0.899497 9.987641\n5328 3.103552 -0.003532 -0.001434 -0.011898 0.763933 0.898128 9.983790\n5329 3.109535 -0.004139 -0.001253 -0.011744 0.769095 0.876889 9.994346\n5330 3.115660 -0.004296 -0.001455 -0.011066 0.764568 0.877043 9.998898\n5331 3.121574 -0.004130 -0.002282 -0.009860 0.772960 0.893562 10.014867\n5332 3.127545 -0.004040 -0.002550 -0.009670 0.773497 0.895269 10.024090\n5333 3.133708 -0.003808 -0.002689 -0.010469 0.774048 0.901259 10.012717\n5334 3.139802 -0.003539 -0.002410 -0.011065 0.763425 0.909223 10.005757\n5335 3.145835 -0.003896 -0.001713 -0.011582 0.745000 0.916613 10.001866\n5336 3.151944 -0.004065 -0.001764 -0.011607 0.748450 0.902255 9.993766\n5337 3.157948 -0.004635 -0.002200 -0.010983 0.760271 0.865054 9.983784\n5338 3.163937 -0.004502 -0.002679 -0.010814 0.762083 0.864405 9.987534\n5339 3.170091 -0.003881 -0.003114 -0.010694 0.750052 0.872760 9.994507\n5340 3.175946 -0.003747 -0.002765 -0.010684 0.753853 0.873049 10.000887\n5341 3.182006 -0.003601 -0.002587 -0.010371 0.761291 0.887219 10.000294\n5342 3.187904 -0.003686 -0.002685 -0.010591 0.761990 0.900085 9.996778\n5343 3.194548 -0.003954 -0.002622 -0.011220 0.759942 0.898788 9.998152\n5344 3.200283 -0.003794 -0.002515 -0.011087 0.754916 0.884938 10.002723\n5345 3.206150 -0.003479 -0.002256 -0.011241 0.759581 0.857169 10.033471\n5346 3.212275 -0.003089 -0.002343 -0.011459 0.762431 0.868984 10.030919\n5347 3.218379 -0.002965 -0.002962 -0.011353 0.761605 0.904106 10.023186\n5348 3.224356 -0.003340 -0.002846 -0.011381 0.760702 0.900064 10.023441\n5349 3.230428 -0.003482 -0.001846 -0.011541 0.766510 0.888628 10.014157\n5350 3.236315 -0.003605 -0.001465 -0.011303 0.766274 0.889849 10.013141\n5351 3.242369 -0.003878 -0.000677 -0.011294 0.761939 0.872715 10.001562\n5352 3.248506 -0.003833 -0.000785 -0.011138 0.761042 0.852930 10.006068\n5353 3.254520 -0.004090 -0.002286 -0.010724 0.757933 0.864162 10.007075\n5354 3.260698 -0.004214 -0.002612 -0.010658 0.758386 0.887980 10.003050\n5355 3.266829 -0.003616 -0.001926 -0.010735 0.758642 0.892169 10.000378\n5356 3.272661 -0.003685 -0.001472 -0.010772 0.757521 0.884369 10.003937\n5357 3.278732 -0.004115 -0.000901 -0.011350 0.754248 0.894697 10.010132\n5358 3.285357 -0.003603 -0.001758 -0.011424 0.763549 0.902947 10.009899\n5359 3.290747 -0.003523 -0.002054 -0.011276 0.769045 0.898647 10.004205\n5360 3.297284 -0.003478 -0.003003 -0.010676 0.772004 0.894988 10.007832\n5361 3.302864 -0.003603 -0.003292 -0.010509 0.767179 0.900954 10.010680\n5362 3.309263 -0.003564 -0.003209 -0.010580 0.776695 0.896506 10.026489\n5363 3.314950 -0.003651 -0.002671 -0.010820 0.784167 0.882146 10.030824\n5364 3.321222 -0.003913 -0.001802 -0.011080 0.779280 0.876925 10.002205\n5365 3.326971 -0.003973 -0.001618 -0.010697 0.777244 0.879998 9.986308\n5366 3.333287 -0.003879 -0.002011 -0.010792 0.783956 0.861524 9.971043\n5367 3.339030 -0.003747 -0.002242 -0.010611 0.781942 0.855846 9.969601\n5368 3.345188 -0.003606 -0.002872 -0.010210 0.781503 0.897787 9.976277\n5369 3.351250 -0.003669 -0.002565 -0.010235 0.768556 0.915425 9.975748\n5370 3.357231 -0.003634 -0.002492 -0.010497 0.746371 0.908007 9.983650\n5371 3.363338 -0.003841 -0.002443 -0.010750 0.748224 0.896361 9.991266\n5372 3.369341 -0.003780 -0.002048 -0.011783 0.760447 0.887180 10.006672\n5373 3.375340 -0.003513 -0.001670 -0.012084 0.771117 0.877787 10.003702\n5374 3.381380 -0.003980 -0.001622 -0.011324 0.783626 0.849226 9.998322\n5375 3.387421 -0.004415 -0.002290 -0.010555 0.778559 0.854972 10.003589\n5376 3.393551 -0.003882 -0.003280 -0.009383 0.776302 0.893188 10.019358\n5377 3.399537 -0.003791 -0.003541 -0.009378 0.772871 0.904770 10.016471\n5378 3.405630 -0.003895 -0.003417 -0.010414 0.767817 0.899194 10.008821\n5379 3.411549 -0.003861 -0.002761 -0.010637 0.764871 0.901580 9.999677\n5380 3.417717 -0.003904 -0.001875 -0.011164 0.768498 0.922718 10.000488\n5381 3.423552 -0.003885 -0.001672 -0.011789 0.773465 0.910117 10.002866\n5382 3.429715 -0.003948 -0.002857 -0.012025 0.776869 0.870466 9.998391\n5383 3.435723 -0.004196 -0.003371 -0.011555 0.775801 0.873824 9.989592\n5384 3.441820 -0.004160 -0.003349 -0.010746 0.761591 0.906916 9.992846\n5385 3.447672 -0.004018 -0.003027 -0.010350 0.755908 0.903841 9.997122\n5386 3.453979 -0.004492 -0.002105 -0.010261 0.754678 0.906001 9.992795\n5387 3.459826 -0.004677 -0.001539 -0.010692 0.752467 0.915724 9.985775\n5388 3.466013 -0.003797 -0.001016 -0.011368 0.750390 0.904737 9.993494\n5389 3.472025 -0.003483 -0.001377 -0.011420 0.763447 0.888945 9.992085\n5390 3.478092 -0.004190 -0.001896 -0.011249 0.773085 0.872266 9.993857\n5391 3.484097 -0.004334 -0.002002 -0.010885 0.762337 0.886685 10.010014\n5392 3.490094 -0.004121 -0.002434 -0.010331 0.757923 0.897918 10.023046\n5393 3.496217 -0.004205 -0.002444 -0.010491 0.757676 0.890540 10.027544\n5394 3.502139 -0.004748 -0.002029 -0.011223 0.741723 0.895914 10.030448\n5395 3.508310 -0.004919 -0.001820 -0.011268 0.737337 0.898964 10.024850\n5396 3.514157 -0.004555 -0.002096 -0.010856 0.738086 0.874360 10.005957\n5397 3.520463 -0.004575 -0.002152 -0.010723 0.742375 0.869225 10.004933\n5398 3.526402 -0.004711 -0.003134 -0.010308 0.760598 0.901013 10.000701\n5399 3.532296 -0.004149 -0.003117 -0.010341 0.766421 0.917583 9.996770\n5400 3.538427 -0.003301 -0.002469 -0.010876 0.770754 0.906698 9.999833\n5401 3.544514 -0.003449 -0.002235 -0.011275 0.768667 0.901101 10.007937\n5402 3.550780 -0.003547 -0.002204 -0.012029 0.764419 0.910088 10.010400\n5403 3.556589 -0.003551 -0.002130 -0.012502 0.766576 0.904544 10.010559\n5404 3.562762 -0.003376 -0.001850 -0.011644 0.780457 0.879763 10.027363\n5405 3.568556 -0.003378 -0.002309 -0.011238 0.781863 0.870956 10.029761\n5406 3.574707 -0.002990 -0.003039 -0.011200 0.773007 0.882078 10.039455\n5407 3.580716 -0.003200 -0.003056 -0.011050 0.771014 0.884159 10.037501\n5408 3.586638 -0.003805 -0.002626 -0.010833 0.762437 0.890443 10.006817\n5409 3.592942 -0.004044 -0.002413 -0.010639 0.755041 0.899922 9.988148\n5410 3.598814 -0.004266 -0.002056 -0.010539 0.772700 0.910723 9.985430\n5411 3.604855 -0.004093 -0.001695 -0.010589 0.787271 0.896944 9.997626\n5412 3.610964 -0.003361 -0.001396 -0.011182 0.798176 0.869627 10.036969\n5413 3.617195 -0.003650 -0.001692 -0.011136 0.787926 0.877023 10.045463\n5414 3.623063 -0.004093 -0.002910 -0.011086 0.761022 0.902052 10.038199\n5415 3.629215 -0.004097 -0.003024 -0.010883 0.751026 0.901426 10.029272\n5416 3.635197 -0.004030 -0.002069 -0.010964 0.755730 0.882915 10.018382\n5417 3.641188 -0.004009 -0.001686 -0.011232 0.772410 0.882220 10.007726\n5418 3.647223 -0.003746 -0.001777 -0.011609 0.787632 0.888659 9.984789\n5419 3.653311 -0.003558 -0.001846 -0.011610 0.785078 0.890253 9.981799\n5420 3.659280 -0.003599 -0.001911 -0.011285 0.774699 0.893681 10.000939\n5421 3.665402 -0.003324 -0.002106 -0.010596 0.766206 0.894411 10.010292\n5422 3.671309 -0.003311 -0.002374 -0.009649 0.761345 0.890268 10.017328\n5423 3.677386 -0.003663 -0.002707 -0.009585 0.755146 0.890463 10.022304\n5424 3.683786 -0.004173 -0.002934 -0.010966 0.751676 0.900644 10.010075\n5425 3.689633 -0.004173 -0.002661 -0.011525 0.750797 0.903794 10.006596\n5426 3.695548 -0.004286 -0.002199 -0.011479 0.764694 0.896297 10.011141\n5427 3.701631 -0.004301 -0.002239 -0.011329 0.767475 0.880110 10.015877\n5428 3.707538 -0.003489 -0.002715 -0.010688 0.761737 0.874646 10.025585\n5429 3.714140 -0.003206 -0.002521 -0.010305 0.758304 0.884252 10.029868\n5430 3.719802 -0.002953 -0.002090 -0.010351 0.749206 0.904829 10.015645\n5431 3.726141 -0.002951 -0.001483 -0.011209 0.751707 0.895347 10.014611\n5432 3.731768 -0.003630 -0.001441 -0.011437 0.754116 0.898023 10.019390\n5433 3.738161 -0.004170 -0.001536 -0.011493 0.751799 0.890728 10.026962\n5434 3.743820 -0.004082 -0.001833 -0.011326 0.759385 0.883216 10.019644\n5435 3.750324 -0.003722 -0.003004 -0.011002 0.772334 0.892384 10.006286\n5436 3.755790 -0.003363 -0.003355 -0.011064 0.767666 0.901789 10.005697\n5437 3.762130 -0.002681 -0.002972 -0.011419 0.752527 0.897556 9.999428\n5438 3.767900 -0.002847 -0.002474 -0.011515 0.752224 0.893579 10.002951\n5439 3.774178 -0.003837 -0.002088 -0.011377 0.756237 0.907208 10.027822\n5440 3.780141 -0.004096 -0.002137 -0.011457 0.762606 0.911563 10.042311\n5441 3.786204 -0.003462 -0.001584 -0.011381 0.763977 0.882610 10.048746\n5442 3.792340 -0.003595 -0.001359 -0.011379 0.762875 0.867701 10.039347\n5443 3.798202 -0.003957 -0.001471 -0.010866 0.766590 0.884850 10.018176\n5444 3.804171 -0.004012 -0.001833 -0.010654 0.756300 0.895157 10.021966\n5445 3.810298 -0.004004 -0.002308 -0.010454 0.738821 0.898757 10.032915\n5446 3.816628 -0.003908 -0.002091 -0.010464 0.737267 0.900129 10.037925\n5447 3.822299 -0.003833 -0.001937 -0.011180 0.735419 0.919083 10.027123\n5448 3.828311 -0.004042 -0.002062 -0.011219 0.744684 0.920781 10.018492\n5449 3.834453 -0.003909 -0.002761 -0.010860 0.770002 0.886962 9.993011\n5450 3.840457 -0.003554 -0.002940 -0.010543 0.771781 0.875450 9.976763\n5451 3.846619 -0.003130 -0.003334 -0.010120 0.759721 0.887219 9.963737\n5452 3.852501 -0.002996 -0.003641 -0.010285 0.755244 0.887696 9.954968\n5453 3.858746 -0.003069 -0.003519 -0.010235 0.754646 0.882733 9.973283\n5454 3.864588 -0.003134 -0.003289 -0.010245 0.758922 0.895164 9.981822\n5455 3.870756 -0.003660 -0.002091 -0.010789 0.749559 0.900211 10.005033\n5456 3.876715 -0.003822 -0.001575 -0.011183 0.749365 0.887081 10.016876\n5457 3.882788 -0.003562 -0.001620 -0.010985 0.753076 0.857927 10.003904\n5458 3.888735 -0.003614 -0.001939 -0.010790 0.758024 0.866167 9.992657\n5459 3.894782 -0.003781 -0.002651 -0.010335 0.758950 0.892781 9.978990\n5460 3.900834 -0.003648 -0.002637 -0.010344 0.759821 0.893074 9.977455\n5461 3.906886 -0.003365 -0.001967 -0.010361 0.762241 0.894302 9.989221\n5462 3.913114 -0.003008 -0.001975 -0.010411 0.760507 0.900171 9.986890\n5463 3.918963 -0.003322 -0.002075 -0.011255 0.756794 0.900344 9.988970\n5464 3.925121 -0.003577 -0.002598 -0.011537 0.760824 0.895348 9.999174\n5465 3.931126 -0.003290 -0.003454 -0.011140 0.762258 0.894717 10.017400\n5466 3.937203 -0.003169 -0.003361 -0.010830 0.762391 0.897200 10.018695\n5467 3.943081 -0.003207 -0.003193 -0.010524 0.763203 0.890332 9.996919\n5468 3.949394 -0.003373 -0.003274 -0.010540 0.758788 0.878619 9.981551\n5469 3.955143 -0.003921 -0.002545 -0.011195 0.751312 0.880523 9.970586\n5470 3.961405 -0.004278 -0.002179 -0.011684 0.750934 0.890369 9.973284\n5471 3.967299 -0.003911 -0.002097 -0.011647 0.765058 0.880951 9.990523\n5472 3.973332 -0.003667 -0.002343 -0.011216 0.775086 0.859520 9.999837\n5473 3.979554 -0.003577 -0.002619 -0.010871 0.776422 0.859091 10.009262\n5474 3.985431 -0.003792 -0.002591 -0.010833 0.768090 0.875414 10.010020\n5475 3.991571 -0.003390 -0.002816 -0.010679 0.754825 0.894749 9.999038\n5476 3.997613 -0.003243 -0.002494 -0.010629 0.754105 0.900280 9.988322\n5477 4.003563 -0.003237 -0.001854 -0.011118 0.743890 0.913945 9.980779\n5478 4.009532 -0.003439 -0.001653 -0.011417 0.744045 0.917196 9.984770\n5479 4.015673 -0.003096 -0.001355 -0.011439 0.757573 0.874300 10.013376\n5480 4.021701 -0.003370 -0.001501 -0.011100 0.760793 0.852407 10.025400\n5481 4.027752 -0.003665 -0.002185 -0.010493 0.761840 0.875370 10.035268\n5482 4.033863 -0.003630 -0.002423 -0.010309 0.767072 0.898124 10.018831\n5483 4.039877 -0.003752 -0.002539 -0.009746 0.765996 0.903760 9.998403\n5484 4.046026 -0.003867 -0.002110 -0.009757 0.763573 0.901408 10.002348\n5485 4.051980 -0.004508 -0.001492 -0.010664 0.770379 0.892996 10.014187\n5486 4.058057 -0.004586 -0.001761 -0.011126 0.779871 0.877587 10.019616\n5487 4.063975 -0.004313 -0.001901 -0.011474 0.788737 0.850191 10.015747\n5488 4.070115 -0.004410 -0.001936 -0.011183 0.785997 0.853819 10.016517\n5489 4.076198 -0.004014 -0.002777 -0.010956 0.771654 0.883837 10.012045\n5490 4.082849 -0.003686 -0.002652 -0.009992 0.769823 0.878253 10.027628\n5491 4.088324 -0.003684 -0.002733 -0.010053 0.767418 0.874149 10.039239\n5492 4.094165 -0.003450 -0.002737 -0.010410 0.759060 0.879480 10.041829\n5493 4.100281 -0.003675 -0.002109 -0.011600 0.752376 0.896378 10.024682\n5494 4.106886 -0.004066 -0.001665 -0.011991 0.756014 0.888406 10.014022\n5495 4.112473 -0.004773 -0.001149 -0.012037 0.773528 0.863081 10.011511\n5496 4.118934 -0.004853 -0.002203 -0.010711 0.768318 0.886384 10.006328\n5497 4.124523 -0.004662 -0.002822 -0.010106 0.758233 0.892964 10.000092\n5498 4.131056 -0.004234 -0.002967 -0.010199 0.761252 0.891708 10.012921\n5499 4.136707 -0.004248 -0.002664 -0.010821 0.762734 0.895612 10.019438\n5500 4.143035 -0.004547 -0.002269 -0.011930 0.758657 0.912378 10.007098\n5501 4.148663 -0.004228 -0.002116 -0.012154 0.762781 0.900108 10.007083\n5502 4.155162 -0.003851 -0.002387 -0.011867 0.773563 0.854252 10.018544\n5503 4.160668 -0.003670 -0.002847 -0.011509 0.776146 0.857229 10.018611\n5504 4.167140 -0.003169 -0.002685 -0.010547 0.766410 0.885059 10.022167\n5505 4.172779 -0.003105 -0.002461 -0.010023 0.763556 0.881742 10.018443\n5506 4.179097 -0.003350 -0.001797 -0.009796 0.761323 0.885174 10.010141\n5507 4.184883 -0.003688 -0.001588 -0.010280 0.766515 0.901623 10.008088\n5508 4.191072 -0.004155 -0.001785 -0.011234 0.767825 0.902470 10.006553\n5509 4.196929 -0.004148 -0.001632 -0.011824 0.765334 0.882398 10.016939\n5510 4.203008 -0.004143 -0.001757 -0.011842 0.747730 0.868109 10.008615\n5511 4.209065 -0.004271 -0.001857 -0.011151 0.745292 0.874259 9.993011\n5512 4.215283 -0.003903 -0.002063 -0.010318 0.758221 0.886800 9.981383\n5513 4.221083 -0.003711 -0.002360 -0.009949 0.763367 0.884825 9.980144\n5514 4.227150 -0.003756 -0.002087 -0.010366 0.762891 0.907230 9.976838\n5515 4.233053 -0.003503 -0.001894 -0.010964 0.763212 0.920275 9.986827\n5516 4.239229 -0.003079 -0.002116 -0.011646 0.768641 0.899885 10.004604\n5517 4.245216 -0.003395 -0.002314 -0.011489 0.775913 0.877882 10.012256\n5518 4.251229 -0.003894 -0.002637 -0.011362 0.778296 0.879194 10.013368\n5519 4.257163 -0.004021 -0.002536 -0.011386 0.778081 0.890040 10.012262\n5520 4.263618 -0.003475 -0.001929 -0.010675 0.762787 0.873668 10.013672\n5521 4.269339 -0.003518 -0.001746 -0.010591 0.765092 0.865814 10.008108\n5522 4.275546 -0.003992 -0.001635 -0.010851 0.770253 0.893678 10.003297\n5523 4.281522 -0.004050 -0.001460 -0.010962 0.770127 0.906889 10.006031\n5524 4.287570 -0.004252 -0.001299 -0.011449 0.770839 0.890124 10.001463\n5525 4.293609 -0.004477 -0.001578 -0.011348 0.770347 0.880356 9.988535\n5526 4.299727 -0.004155 -0.002007 -0.010492 0.776649 0.876590 9.982380\n5527 4.305613 -0.003721 -0.001908 -0.009777 0.775913 0.872991 9.985367\n5528 4.311766 -0.003150 -0.001711 -0.009657 0.757710 0.867706 9.999870\n5529 4.317658 -0.003273 -0.001495 -0.010053 0.751032 0.879777 10.004530\n5530 4.323748 -0.003806 -0.001418 -0.011155 0.742122 0.906469 10.005399\n5531 4.329832 -0.003989 -0.001593 -0.011510 0.746489 0.909019 10.004837\n5532 4.335799 -0.003986 -0.002567 -0.011319 0.754069 0.888283 9.997342\n5533 4.341911 -0.004052 -0.002949 -0.011031 0.758315 0.891428 9.995018\n5534 4.347893 -0.004045 -0.003367 -0.010586 0.750926 0.897253 10.014074\n5535 4.353981 -0.003644 -0.003432 -0.010306 0.744036 0.885488 10.013814\n5536 4.359928 -0.003441 -0.003438 -0.009796 0.750099 0.872506 10.006406\n5537 4.365951 -0.003515 -0.003329 -0.009734 0.755040 0.883142 10.001638\n5538 4.372056 -0.003067 -0.002480 -0.010630 0.764325 0.897183 10.001212\n5539 4.378163 -0.003270 -0.002089 -0.011086 0.769139 0.887378 10.013371\n5540 4.384353 -0.003969 -0.002053 -0.011180 0.769879 0.882362 10.037872\n5541 4.390250 -0.003860 -0.002171 -0.011192 0.773426 0.888784 10.029197\n5542 4.396355 -0.003881 -0.002827 -0.010900 0.784538 0.885828 10.002927\n5543 4.402306 -0.003678 -0.002940 -0.010409 0.781246 0.876487 10.001169\n5544 4.408438 -0.003399 -0.002014 -0.009796 0.754237 0.902347 10.009473\n5545 4.414430 -0.003332 -0.001353 -0.009850 0.737428 0.927388 10.005457\n5546 4.420417 -0.003211 -0.001080 -0.010721 0.741312 0.924509 10.014077\n5547 4.426658 -0.003489 -0.001446 -0.011483 0.755694 0.908874 10.014908\n5548 4.432521 -0.003498 -0.002044 -0.011791 0.773977 0.886181 10.005823\n5549 4.438664 -0.003260 -0.002014 -0.011214 0.773530 0.877388 9.997232\n5550 4.444681 -0.003160 -0.002230 -0.009993 0.768568 0.860850 9.996492\n5551 4.450742 -0.003383 -0.002552 -0.009771 0.764417 0.866106 9.993294\n5552 4.456694 -0.003863 -0.002885 -0.010009 0.761196 0.899486 9.997547\n5553 4.462640 -0.003975 -0.002447 -0.010293 0.753416 0.906170 9.991791\n5554 4.468685 -0.003927 -0.001259 -0.010682 0.759015 0.885702 9.992416\n5555 4.474779 -0.003745 -0.001179 -0.011058 0.768803 0.880336 9.996716\n5556 4.481159 -0.003439 -0.001444 -0.011415 0.779316 0.887725 10.009374\n5557 4.486894 -0.003642 -0.001910 -0.011274 0.775302 0.887828 10.016270\n5558 4.493009 -0.004110 -0.002199 -0.010399 0.756470 0.884670 10.019243\n5559 4.499026 -0.004516 -0.002303 -0.010141 0.751759 0.885823 10.013301\n5560 4.505041 -0.004365 -0.002282 -0.010523 0.757292 0.906391 9.996308\n5561 4.511337 -0.003864 -0.002160 -0.010857 0.761112 0.903824 9.995497\n5562 4.517197 -0.004145 -0.001757 -0.011137 0.779858 0.872727 10.010291\n5563 4.523721 -0.004264 -0.001164 -0.012018 0.787889 0.889197 10.015788\n5564 4.529335 -0.003801 -0.001815 -0.011985 0.776271 0.900363 10.012316\n5565 4.535726 -0.004174 -0.002374 -0.011013 0.753270 0.878302 9.977623\n5566 4.541193 -0.004606 -0.002330 -0.010396 0.754359 0.873787 9.976396\n5567 4.547659 -0.004539 -0.002396 -0.009719 0.765623 0.900555 10.011049\n5568 4.553515 -0.004153 -0.002407 -0.010045 0.766852 0.907979 10.031375\n5569 4.559737 -0.003812 -0.002270 -0.011246 0.759730 0.889295 10.047854\n5570 4.565354 -0.003995 -0.002312 -0.011573 0.760196 0.886536 10.042635\n5571 4.571706 -0.003568 -0.002899 -0.012008 0.762532 0.896668 10.036791\n5572 4.577534 -0.003129 -0.003176 -0.012114 0.756980 0.890582 10.026459\n5573 4.583692 -0.002956 -0.003326 -0.011472 0.754999 0.857130 10.007808\n5574 4.589611 -0.003552 -0.003369 -0.011009 0.752854 0.859560 10.009919\n5575 4.595836 -0.003685 -0.003096 -0.010268 0.748952 0.895943 10.000429\n5576 4.601570 -0.003496 -0.002810 -0.010466 0.749125 0.901761 10.000543\n5577 4.607827 -0.004385 -0.002164 -0.010889 0.759094 0.898851 10.003423\n5578 4.613846 -0.004517 -0.001700 -0.011098 0.761841 0.907057 10.011604\n5579 4.619935 -0.004468 -0.001280 -0.011302 0.758908 0.893423 10.019833\n5580 4.625744 -0.004435 -0.001537 -0.011243 0.757171 0.868250 10.015760\n5581 4.631858 -0.004173 -0.001736 -0.010612 0.764559 0.862671 10.010015\n5582 4.637853 -0.004051 -0.001919 -0.010577 0.773681 0.888020 10.006419\n5583 4.643941 -0.003854 -0.002229 -0.011098 0.784460 0.911283 10.003867\n5584 4.650014 -0.003684 -0.002453 -0.011388 0.781681 0.902915 10.010683\n5585 4.655950 -0.004084 -0.003305 -0.011764 0.776735 0.895996 10.002970\n5586 4.661904 -0.004124 -0.003137 -0.011884 0.769827 0.897460 9.999530\n5587 4.668149 -0.004549 -0.002722 -0.011342 0.766478 0.897359 10.000446\n5588 4.673978 -0.004208 -0.002372 -0.010952 0.767328 0.885139 10.002905\n5589 4.680182 -0.003398 -0.001926 -0.010156 0.755798 0.894623 10.007265\n5590 4.686043 -0.003288 -0.001913 -0.010157 0.756526 0.905717 10.011359\n5591 4.692234 -0.002878 -0.002750 -0.010691 0.756059 0.901895 10.022175\n5592 4.698162 -0.003020 -0.003356 -0.010852 0.757874 0.891790 10.022161\n5593 4.704404 -0.003244 -0.003745 -0.010932 0.760601 0.896975 10.012346\n5594 4.710301 -0.003474 -0.003532 -0.010978 0.764005 0.895081 10.011757\n5595 4.716478 -0.004057 -0.003232 -0.010796 0.770999 0.877029 10.010345\n5596 4.722467 -0.004161 -0.002937 -0.010519 0.766510 0.881246 9.998836\n5597 4.728580 -0.003888 -0.002079 -0.009862 0.752253 0.898980 10.002148\n5598 4.734654 -0.003865 -0.001941 -0.009934 0.752049 0.894893 10.016771\n5599 4.740659 -0.003960 -0.002219 -0.011166 0.761666 0.886909 10.026540\n5600 4.746929 -0.004145 -0.002631 -0.011707 0.762302 0.883228 10.020430\n5601 4.752714 -0.004181 -0.002834 -0.011561 0.768264 0.885395 9.995402\n5602 4.758833 -0.003929 -0.002724 -0.011154 0.772756 0.884805 9.993606\n5603 4.764763 -0.004180 -0.002515 -0.010635 0.770725 0.876620 10.011389\n5604 4.770731 -0.004141 -0.002368 -0.010558 0.770085 0.887761 10.006665\n5605 4.776731 -0.003502 -0.001668 -0.010688 0.763200 0.904075 9.994273\n5606 4.782919 -0.003180 -0.001549 -0.010922 0.763158 0.894884 9.997995\n5607 4.789016 -0.003590 -0.001662 -0.010892 0.763713 0.882218 10.007466\n5608 4.794872 -0.003989 -0.001949 -0.010793 0.757982 0.889596 10.005702\n5609 4.800973 -0.004584 -0.002431 -0.011189 0.740115 0.902512 10.003027\n5610 4.806962 -0.004447 -0.002566 -0.010951 0.735040 0.889384 10.006000\n5611 4.813039 -0.003519 -0.002457 -0.010456 0.742499 0.881463 10.007881\n5612 4.818993 -0.003516 -0.002288 -0.010729 0.744219 0.892307 9.999280\n5613 4.825061 -0.003461 -0.001648 -0.011625 0.750256 0.900992 9.981643\n5614 4.831097 -0.003521 -0.001655 -0.011613 0.757257 0.892807 9.990020\n5615 4.837157 -0.003539 -0.002135 -0.011621 0.767609 0.879620 10.021880\n5616 4.843243 -0.003520 -0.002384 -0.011400 0.766625 0.880615 10.023161\n5617 4.849265 -0.003681 -0.002672 -0.010789 0.770367 0.871234 10.030013\n5618 4.855281 -0.003739 -0.002766 -0.010637 0.768366 0.868956 10.031581\n5619 4.861396 -0.003912 -0.002563 -0.010403 0.762034 0.891125 10.006951\n5620 4.867409 -0.003908 -0.002338 -0.010522 0.754922 0.902225 9.992150\n5621 4.873476 -0.004128 -0.001556 -0.010745 0.742819 0.885925 9.990317\n5622 4.879619 -0.004108 -0.001371 -0.010879 0.749948 0.874564 9.992239\n5623 4.885535 -0.004233 -0.002378 -0.011019 0.759266 0.887640 9.982952\n5624 4.891656 -0.004267 -0.002631 -0.011257 0.758385 0.897316 9.980412\n5625 4.897663 -0.004046 -0.002837 -0.011620 0.762700 0.878868 9.984536\n5626 4.903678 -0.004008 -0.002492 -0.011551 0.762216 0.876591 9.991106\n5627 4.909729 -0.004246 -0.002270 -0.011508 0.752925 0.895416 10.019737\n5628 4.915647 -0.003829 -0.002363 -0.011304 0.749884 0.898162 10.024606\n5629 4.921821 -0.003607 -0.002404 -0.011424 0.754079 0.883478 10.024893\n5630 4.927714 -0.003759 -0.002646 -0.011550 0.762668 0.875326 10.027660\n5631 4.933926 -0.003545 -0.003157 -0.011440 0.766912 0.870890 10.021608\n5632 4.939907 -0.003614 -0.003216 -0.011276 0.773894 0.870633 10.026512\n5633 4.946060 -0.004227 -0.002812 -0.010764 0.782027 0.872150 10.038054\n5634 4.952517 -0.004285 -0.002959 -0.010634 0.779668 0.879005 10.033359\n5635 4.958116 -0.003658 -0.003146 -0.010400 0.770927 0.897919 10.008251\n5636 4.964508 -0.003213 -0.002425 -0.010877 0.778912 0.897763 10.004929\n5637 4.970154 -0.003378 -0.002303 -0.010877 0.784802 0.891169 10.009282\n5638 4.976532 -0.003907 -0.002381 -0.010872 0.779871 0.901493 10.023788\n5639 4.982126 -0.004006 -0.002210 -0.010787 0.774498 0.900963 10.018555\n5640 4.988564 -0.003961 -0.002265 -0.011068 0.760861 0.877970 10.008449\n5641 4.994121 -0.003967 -0.002577 -0.010962 0.756516 0.879908 10.005755\n5642 5.000562 -0.004171 -0.003089 -0.010686 0.742682 0.898321 10.004815\n5643 5.006311 -0.003804 -0.003038 -0.010696 0.740221 0.896356 10.016421\n5644 5.012821 -0.003861 -0.002455 -0.010817 0.748826 0.879014 10.030051\n5645 5.018503 -0.004222 -0.002625 -0.011014 0.754239 0.872508 10.025671\n5646 5.024544 -0.004633 -0.003234 -0.011130 0.755975 0.878173 10.013449\n5647 5.030675 -0.004659 -0.003350 -0.011128 0.756346 0.882755 10.022243\n5648 5.036750 -0.004593 -0.002789 -0.011329 0.763135 0.875239 10.024986\n5649 5.042686 -0.004727 -0.002884 -0.011186 0.758068 0.882593 10.023627\n5650 5.048747 -0.004471 -0.002398 -0.010910 0.755074 0.896656 10.017944\n5651 5.054752 -0.004234 -0.002208 -0.010811 0.764847 0.889354 10.014614\n5652 5.060893 -0.004580 -0.002068 -0.010638 0.777222 0.885981 9.996948\n5653 5.066782 -0.004754 -0.002194 -0.010634 0.771234 0.893878 9.992813\n5654 5.072769 -0.005013 -0.002585 -0.011215 0.750324 0.886893 9.981994\n5655 5.078893 -0.004781 -0.002365 -0.010917 0.745911 0.873645 9.989157\n5656 5.085151 -0.004051 -0.002434 -0.009985 0.743272 0.878187 9.994065\n5657 5.090847 -0.004051 -0.002397 -0.009946 0.745290 0.899691 9.996622\n5658 5.096991 -0.003981 -0.001922 -0.010932 0.759924 0.905442 9.997732\n5659 5.102990 -0.003718 -0.002009 -0.011065 0.769283 0.893566 9.988734\n5660 5.109108 -0.003382 -0.002245 -0.011049 0.765737 0.891201 9.966331\n5661 5.115077 -0.003572 -0.002268 -0.011134 0.764146 0.888462 9.977920\n5662 5.121160 -0.003753 -0.002976 -0.011119 0.764237 0.879726 9.999806\n5663 5.127210 -0.003851 -0.003501 -0.010990 0.761873 0.879675 9.992188\n5664 5.133237 -0.004235 -0.003028 -0.010680 0.766675 0.886268 9.980068\n5665 5.139242 -0.004269 -0.002530 -0.010604 0.766063 0.892688 9.973960\n5666 5.145366 -0.003996 -0.001746 -0.010394 0.765856 0.877955 9.972754\n5667 5.151330 -0.003993 -0.001796 -0.010792 0.768307 0.877080 9.977377\n5668 5.157376 -0.004169 -0.002086 -0.011340 0.760524 0.898240 9.973180\n5669 5.163558 -0.004067 -0.002223 -0.011502 0.756533 0.902743 9.980493\n5670 5.169456 -0.004124 -0.002723 -0.012017 0.770462 0.890899 10.011554\n5671 5.175752 -0.004180 -0.002973 -0.011910 0.772747 0.885357 10.005776\n5672 5.181415 -0.004193 -0.002922 -0.011272 0.762686 0.879244 9.998995\n5673 5.187422 -0.004346 -0.002945 -0.010901 0.771326 0.881035 10.000112\n5674 5.193598 -0.004032 -0.002203 -0.010598 0.778093 0.891448 10.022161\n5675 5.199526 -0.003833 -0.002106 -0.010634 0.775961 0.889221 10.026235\n5676 5.205772 -0.004388 -0.002466 -0.010960 0.764486 0.907628 10.010025\n5677 5.211801 -0.004424 -0.002436 -0.011294 0.762357 0.914554 10.005357\n5678 5.217913 -0.004054 -0.001907 -0.011321 0.758080 0.896171 10.002967\n5679 5.223800 -0.003808 -0.002087 -0.011269 0.756240 0.893339 10.005929\n5680 5.229896 -0.002971 -0.002399 -0.011525 0.765014 0.901601 10.006294\n5681 5.235799 -0.002848 -0.002741 -0.011383 0.772250 0.892162 10.013165\n5682 5.241869 -0.003379 -0.003073 -0.010816 0.780470 0.876852 10.007825\n5683 5.247894 -0.003721 -0.002846 -0.010653 0.780356 0.880486 10.004510\n5684 5.253967 -0.004103 -0.002164 -0.010808 0.763300 0.894042 10.005097\n5685 5.260154 -0.004101 -0.001819 -0.011000 0.761855 0.890099 10.007687\n5686 5.266081 -0.004373 -0.002076 -0.010976 0.760763 0.879425 10.012142\n5687 5.272147 -0.004158 -0.001994 -0.011002 0.754690 0.885843 10.001297\n5688 5.278403 -0.003679 -0.001628 -0.011451 0.758993 0.872643 9.985592\n5689 5.284272 -0.003507 -0.001842 -0.011603 0.760290 0.854774 9.981261\n5690 5.290138 -0.004204 -0.001646 -0.011339 0.753898 0.851673 9.989577\n5691 5.296298 -0.004389 -0.001604 -0.010978 0.747595 0.866948 9.998287\n5692 5.302379 -0.004556 -0.001546 -0.010524 0.754720 0.882296 10.005994\n5693 5.308365 -0.004781 -0.001745 -0.010488 0.759531 0.884121 10.016026\n5694 5.314354 -0.004698 -0.001205 -0.011038 0.746716 0.902846 10.009314\n5695 5.320489 -0.004271 -0.001011 -0.011008 0.742355 0.913987 10.007866\n5696 5.326604 -0.003633 -0.001551 -0.010458 0.757296 0.901604 10.003219\n5697 5.332612 -0.003764 -0.001794 -0.010224 0.763284 0.885898 10.012324\n5698 5.338741 -0.003429 -0.002825 -0.010307 0.760300 0.882213 10.011033\n5699 5.344566 -0.002895 -0.003194 -0.010527 0.755006 0.888267 10.008824\n5700 5.350858 -0.002596 -0.002850 -0.010980 0.759858 0.879817 10.032997\n5701 5.356626 -0.002984 -0.002570 -0.011306 0.765146 0.873319 10.043412\n5702 5.362671 -0.003759 -0.002397 -0.011654 0.763602 0.886547 10.021017\n5703 5.368839 -0.003441 -0.002674 -0.011466 0.769157 0.883555 9.998563\n5704 5.374801 -0.003703 -0.002590 -0.011120 0.789639 0.858550 9.996698\n5705 5.381542 -0.004391 -0.002243 -0.010895 0.781607 0.872142 10.011427\n5706 5.386933 -0.004309 -0.002012 -0.010752 0.768584 0.885951 10.008547\n5707 5.393484 -0.004063 -0.001739 -0.010634 0.762527 0.882515 10.015397\n5708 5.398954 -0.004133 -0.001978 -0.010823 0.763818 0.878643 10.007539\n5709 5.405572 -0.004117 -0.001602 -0.010674 0.753861 0.902322 10.005852\n5710 5.411213 -0.004294 -0.001576 -0.010574 0.748727 0.913657 10.006464\n5711 5.417533 -0.004015 -0.002072 -0.010559 0.758336 0.903045 9.999330\n5712 5.423185 -0.003879 -0.002303 -0.010578 0.766977 0.888493 10.000060\n5713 5.429595 -0.003985 -0.002962 -0.010892 0.767836 0.901108 10.002765\n5714 5.435264 -0.003827 -0.003488 -0.011217 0.765496 0.899293 10.004966\n5715 5.441526 -0.003996 -0.003015 -0.011631 0.766304 0.876097 10.004056\n5716 5.447539 -0.004279 -0.002614 -0.011690 0.766811 0.880858 9.995484\n5717 5.453610 -0.004504 -0.002350 -0.011685 0.758776 0.910711 10.000570\n5718 5.459523 -0.004300 -0.002227 -0.011505 0.761487 0.906452 10.012867\n5719 5.465914 -0.003773 -0.002479 -0.010835 0.750265 0.896727 10.002095\n5720 5.471539 -0.003620 -0.002619 -0.010513 0.752857 0.907031 9.995371\n5721 5.477953 -0.003862 -0.002838 -0.010952 0.771707 0.922716 10.002879\n5722 5.483651 -0.003802 -0.002653 -0.010957 0.783089 0.906841 10.003908\n5723 5.489736 -0.004173 -0.001883 -0.011073 0.781226 0.883717 9.991523\n5724 5.495618 -0.004199 -0.001827 -0.011204 0.773535 0.898671 9.980783\n5725 5.501714 -0.004247 -0.002353 -0.011370 0.761512 0.907833 9.989497\n5726 5.507733 -0.004030 -0.002485 -0.011419 0.766109 0.898984 9.998380\n5727 5.513895 -0.004350 -0.001757 -0.011455 0.769973 0.880532 10.018517\n5728 5.519781 -0.004294 -0.001657 -0.011178 0.773136 0.886084 10.022573\n5729 5.526033 -0.004068 -0.002211 -0.010734 0.767397 0.892051 10.013816\n5730 5.531896 -0.004139 -0.002366 -0.010935 0.763738 0.885906 10.021858\n5731 5.537929 -0.004728 -0.002798 -0.011149 0.755308 0.894240 10.037240\n5732 5.543956 -0.004897 -0.002810 -0.010980 0.761663 0.901381 10.032882\n5733 5.550083 -0.004010 -0.002951 -0.010816 0.771019 0.896725 9.989621\n5734 5.555853 -0.003793 -0.003052 -0.010716 0.769534 0.885203 9.981947\n5735 5.562015 -0.003551 -0.003046 -0.010931 0.758732 0.892917 9.970676\n5736 5.568099 -0.003546 -0.002973 -0.010982 0.758299 0.898234 9.973908\n5737 5.574135 -0.003617 -0.003164 -0.011357 0.760250 0.878506 10.021431\n5738 5.580214 -0.003952 -0.002971 -0.011337 0.754842 0.866279 10.036400\n5739 5.586240 -0.003599 -0.002378 -0.011554 0.752549 0.879630 10.025100\n5740 5.592368 -0.003590 -0.002084 -0.011542 0.756794 0.894954 10.010810\n5741 5.598351 -0.003323 -0.001597 -0.011370 0.780749 0.895631 10.005613\n5742 5.604324 -0.003464 -0.001795 -0.011444 0.789484 0.886428 10.005414\n5743 5.610390 -0.004044 -0.002260 -0.011245 0.775017 0.908252 9.993169\n5744 5.616319 -0.003909 -0.002439 -0.010840 0.765957 0.917681 9.987143\n5745 5.622537 -0.003347 -0.002355 -0.010710 0.759310 0.907238 10.002029\n5746 5.628458 -0.003338 -0.002187 -0.010678 0.759276 0.904531 10.007315\n5747 5.634531 -0.003376 -0.001708 -0.010518 0.763302 0.920268 10.008656\n5748 5.640547 -0.003336 -0.001664 -0.010345 0.760781 0.916630 10.007993\n5749 5.646737 -0.003556 -0.001688 -0.010543 0.762140 0.898194 10.000128\n5750 5.652545 -0.003530 -0.001945 -0.010299 0.766730 0.892692 9.996424\n5751 5.658675 -0.003412 -0.002026 -0.010400 0.766104 0.889288 9.985215\n5752 5.664684 -0.003442 -0.001848 -0.010501 0.766954 0.885390 9.980060\n5753 5.670731 -0.004320 -0.001494 -0.010924 0.757747 0.870110 9.990910\n5754 5.677082 -0.004505 -0.001360 -0.010920 0.755993 0.879500 9.997399\n5755 5.682801 -0.004054 -0.001657 -0.010836 0.758094 0.916223 9.987543\n5756 5.688900 -0.003556 -0.001630 -0.010486 0.768705 0.912636 9.992767\n5757 5.694995 -0.003117 -0.001984 -0.010043 0.770071 0.885357 10.000219\n5758 5.700989 -0.003388 -0.002351 -0.010206 0.758275 0.899253 10.002353\n5759 5.706998 -0.003522 -0.002923 -0.010722 0.742110 0.918589 10.010877\n5760 5.713098 -0.003339 -0.002763 -0.010679 0.744150 0.901000 10.018675\n5761 5.719098 -0.003097 -0.002281 -0.011037 0.762201 0.881005 10.007433\n5762 5.725117 -0.003359 -0.002146 -0.011355 0.766302 0.892533 9.998111\n5763 5.731247 -0.003443 -0.002466 -0.011251 0.766460 0.893520 9.982515\n5764 5.737229 -0.003830 -0.002619 -0.011008 0.769868 0.882077 9.982600\n5765 5.743628 -0.004320 -0.002532 -0.010728 0.768866 0.880078 9.987890\n5766 5.749367 -0.004076 -0.002148 -0.011095 0.757922 0.889552 9.998958\n5767 5.755398 -0.003742 -0.001685 -0.011188 0.749422 0.900447 10.010130\n5768 5.761396 -0.003798 -0.001751 -0.011343 0.753397 0.890819 10.015480\n5769 5.767523 -0.004209 -0.002081 -0.011118 0.753245 0.884673 10.013733\n5770 5.773492 -0.004174 -0.002232 -0.010771 0.751450 0.891476 10.014893\n5771 5.779562 -0.003791 -0.002175 -0.010178 0.749016 0.869206 10.011001\n5772 5.785684 -0.003986 -0.002218 -0.010056 0.749566 0.862526 10.008492\n5773 5.791586 -0.004317 -0.002999 -0.010446 0.746156 0.888026 10.006833\n5774 5.797711 -0.004187 -0.003220 -0.010882 0.744518 0.895931 10.019305\n5775 5.803654 -0.004019 -0.002739 -0.011222 0.741755 0.895337 10.024785\n5776 5.810504 -0.004184 -0.002344 -0.011185 0.745312 0.902102 10.010199\n5777 5.816856 -0.004031 -0.002092 -0.010955 0.766757 0.914012 9.970938\n5778 5.822771 -0.003909 -0.001882 -0.010693 0.769263 0.881089 9.962933\n5779 5.828773 -0.003776 -0.001924 -0.010781 0.765154 0.862436 9.970581\n5780 5.834859 -0.003516 -0.002081 -0.010628 0.760905 0.875254 9.996130\n5781 5.841001 -0.003503 -0.002167 -0.010893 0.763294 0.898844 10.008925\n5782 5.847033 -0.003460 -0.001635 -0.010840 0.763763 0.893556 10.009198\n5783 5.853001 -0.003523 -0.001578 -0.010724 0.761474 0.881002 9.999082\n5784 5.859006 -0.003685 -0.002613 -0.010611 0.760714 0.888008 9.998202\n5785 5.865156 -0.003466 -0.003035 -0.010436 0.760010 0.900503 9.997845\n5786 5.871087 -0.003879 -0.003093 -0.009688 0.762049 0.885384 9.997836\n5787 5.877221 -0.003741 -0.002823 -0.009422 0.769344 0.882714 9.992816\n5788 5.883087 -0.003391 -0.002885 -0.010024 0.762121 0.907224 9.981134\n5789 5.889206 -0.003582 -0.002470 -0.010529 0.764528 0.903570 9.986046\n5790 5.895208 -0.004117 -0.002106 -0.011630 0.759728 0.867028 9.987352\n5791 5.901214 -0.004105 -0.002149 -0.011774 0.757512 0.868588 9.978230\n5792 5.907396 -0.003712 -0.002065 -0.011040 0.757580 0.889566 9.998474\n5793 5.913318 -0.003580 -0.002228 -0.010952 0.753557 0.888844 10.007071\n5794 5.919326 -0.003783 -0.002698 -0.010882 0.754418 0.887550 10.008839\n5795 5.925320 -0.003647 -0.002580 -0.010466 0.753494 0.887785 10.011519\n5796 5.931617 -0.003630 -0.002467 -0.010136 0.749297 0.891639 10.013434\n5797 5.937569 -0.003787 -0.002658 -0.010311 0.749518 0.887617 10.010947\n5798 5.943568 -0.004230 -0.002566 -0.010646 0.745146 0.880148 10.026690\n5799 5.949616 -0.004515 -0.002538 -0.010504 0.744088 0.884462 10.038857\n5800 5.955526 -0.004107 -0.002236 -0.010381 0.758534 0.894602 10.049809\n5801 5.961646 -0.003634 -0.001873 -0.010504 0.763303 0.890940 10.037691\n5802 5.967756 -0.003569 -0.001766 -0.011020 0.764249 0.886895 10.021068\n5803 5.973768 -0.003698 -0.002030 -0.011004 0.763816 0.895594 10.017716\n5804 5.979790 -0.003110 -0.002624 -0.011026 0.767496 0.895446 10.011085\n5805 5.985988 -0.002951 -0.002585 -0.010946 0.767091 0.882521 10.000538\n5806 5.991865 -0.003138 -0.001982 -0.011241 0.770545 0.877509 9.993877\n5807 5.998115 -0.003464 -0.001742 -0.010995 0.770782 0.879070 9.992911\n5808 6.003888 -0.003601 -0.001680 -0.010391 0.778485 0.859472 10.011456\n5809 6.009939 -0.003445 -0.002006 -0.009940 0.775415 0.854050 10.012871\n5810 6.015951 -0.003346 -0.003007 -0.009467 0.760033 0.880580 10.004741\n5811 6.022005 -0.003168 -0.002985 -0.009783 0.753948 0.896359 10.015210\n5812 6.028120 -0.003641 -0.002713 -0.010772 0.752058 0.898824 10.018641\n5813 6.034071 -0.004042 -0.002479 -0.011397 0.752798 0.888003 10.017941\n5814 6.041041 -0.004775 -0.002392 -0.011836 0.771235 0.903197 10.016114\n5815 6.047172 -0.003840 -0.002523 -0.011239 0.779392 0.904217 10.016315\n5816 6.053265 -0.003576 -0.002416 -0.011045 0.775900 0.890473 10.018066\n5817 6.059296 -0.003933 -0.003228 -0.010798 0.752957 0.888055 9.999350\n5818 6.065263 -0.003928 -0.003179 -0.010853 0.749997 0.895420 9.988604\n5819 6.071297 -0.003704 -0.002242 -0.011375 0.746346 0.899193 9.991022\n5820 6.077274 -0.003594 -0.001752 -0.011248 0.743771 0.886830 9.992329\n5821 6.083595 -0.003339 -0.001593 -0.010770 0.755313 0.885559 10.002111\n5822 6.089697 -0.003242 -0.001658 -0.010626 0.758849 0.887365 10.008646\n5823 6.095542 -0.003338 -0.002797 -0.010289 0.771111 0.867247 10.027714\n5824 6.101573 -0.003771 -0.003243 -0.010240 0.769377 0.863908 10.022986\n5825 6.107543 -0.003619 -0.002817 -0.010470 0.764175 0.876324 10.001930\n5826 6.113520 -0.003248 -0.002290 -0.010560 0.764677 0.892930 10.006448\n5827 6.119686 -0.002756 -0.001354 -0.010557 0.773470 0.885932 10.025187\n5828 6.125662 -0.003042 -0.001004 -0.010776 0.771711 0.875330 10.021557\n5829 6.131727 -0.003710 -0.001250 -0.011683 0.765734 0.895069 10.016435\n5830 6.137799 -0.003887 -0.001540 -0.011709 0.767453 0.903428 10.020595\n5831 6.143815 -0.003732 -0.001570 -0.011061 0.775668 0.894858 9.997513\n5832 6.149823 -0.003988 -0.001753 -0.010772 0.777513 0.889494 9.987356\n5833 6.156026 -0.004094 -0.002134 -0.010470 0.772130 0.908067 9.992615\n5834 6.161957 -0.003962 -0.002347 -0.010466 0.773560 0.906081 9.993072\n5835 6.168071 -0.003800 -0.002109 -0.010682 0.763494 0.879542 9.995768\n5836 6.173962 -0.004079 -0.002140 -0.010856 0.755789 0.887365 9.999941\n5837 6.180066 -0.003990 -0.002279 -0.011348 0.758219 0.890440 9.994119\n5838 6.186230 -0.003938 -0.002525 -0.011182 0.765415 0.871803 9.995658\n5839 6.192457 -0.003432 -0.002602 -0.010400 0.769287 0.857722 10.007827\n5840 6.198270 -0.003280 -0.002711 -0.009978 0.766410 0.871599 10.012955\n5841 6.204249 -0.003053 -0.002896 -0.010108 0.764650 0.898958 10.017555\n5842 6.210305 -0.003303 -0.002454 -0.010396 0.768674 0.899332 10.018169\n5843 6.216263 -0.004142 -0.001700 -0.011063 0.755613 0.883301 10.005238\n5844 6.222245 -0.004311 -0.001769 -0.011323 0.757067 0.890694 10.002741\n5845 6.228318 -0.003707 -0.002069 -0.011431 0.762698 0.897025 10.010397\n5846 6.234512 -0.002969 -0.002460 -0.010957 0.765263 0.879525 10.009186\n5847 6.240582 -0.002781 -0.003393 -0.010255 0.753155 0.867807 10.016404\n5848 6.246642 -0.002982 -0.003540 -0.010075 0.750276 0.880080 10.023144\n5849 6.252647 -0.003007 -0.003023 -0.010110 0.764382 0.903775 10.032868\n5850 6.258750 -0.003390 -0.002517 -0.010716 0.765800 0.908059 10.030853\n5851 6.264705 -0.004353 -0.002047 -0.011027 0.766413 0.910722 10.019092\n5852 6.270694 -0.004359 -0.001971 -0.011060 0.764381 0.913963 10.012230\n5853 6.276620 -0.003689 -0.002420 -0.011219 0.759449 0.879957 10.002756\n5854 6.283256 -0.003819 -0.002541 -0.011145 0.760517 0.880008 10.009084\n5855 6.288710 -0.003507 -0.002735 -0.010673 0.771440 0.913148 10.007259\n5856 6.295621 -0.003908 -0.002049 -0.010093 0.757100 0.919698 10.022731\n5857 6.300992 -0.004436 -0.001581 -0.010233 0.756357 0.906464 10.032090\n5858 6.307520 -0.004782 -0.001075 -0.010548 0.754796 0.893304 10.022741\n5859 6.313114 -0.004603 -0.000688 -0.010901 0.754685 0.894599 10.013202\n5860 6.319494 -0.004236 -0.000765 -0.011050 0.753346 0.882559 10.014023\n5861 6.325114 -0.003850 -0.001249 -0.010952 0.768062 0.873850 10.016366\n5862 6.331513 -0.003085 -0.002280 -0.010131 0.774512 0.876360 10.006384\n5863 6.337197 -0.002919 -0.002666 -0.010094 0.765484 0.887685 10.001815\n5864 6.343563 -0.002995 -0.002605 -0.010601 0.764466 0.895242 9.991888\n5865 6.349186 -0.003273 -0.002210 -0.011070 0.771779 0.898891 9.977986\n5866 6.355612 -0.003816 -0.002521 -0.011785 0.775907 0.913829 9.969614\n5867 6.361264 -0.003180 -0.002258 -0.011884 0.778998 0.908431 9.973944\n5868 6.367572 -0.001988 -0.002191 -0.011453 0.774385 0.876471 9.982636\n5869 6.373377 -0.002397 -0.002414 -0.011045 0.776238 0.864790 9.995114\n5870 6.379612 -0.003248 -0.003064 -0.010263 0.786120 0.888686 10.021409\n5871 6.385582 -0.003384 -0.003278 -0.010172 0.778480 0.910855 10.024188\n5872 6.391597 -0.003689 -0.002828 -0.010432 0.764023 0.905552 10.015573\n5873 6.397803 -0.003728 -0.002540 -0.010757 0.764927 0.893887 10.013569\n5874 6.403551 -0.003482 -0.001682 -0.011729 0.767373 0.884663 9.997488\n5875 6.409640 -0.003219 -0.001391 -0.012160 0.767903 0.878892 9.995917\n5876 6.415656 -0.003492 -0.002012 -0.012012 0.765870 0.868499 10.005051\n5877 6.421729 -0.003875 -0.002353 -0.011349 0.768042 0.879547 10.004896\n5878 6.427830 -0.003956 -0.002031 -0.010008 0.772539 0.905717 10.008457\n5879 6.433808 -0.003733 -0.001651 -0.009910 0.765581 0.904885 10.013562\n5880 6.439775 -0.003821 -0.000658 -0.010244 0.758222 0.886053 10.013809\n5881 6.445859 -0.004007 -0.000499 -0.010799 0.767449 0.890109 10.011052\n5882 6.451909 -0.004057 -0.000730 -0.010983 0.765698 0.901966 9.990469\n5883 6.457919 -0.003468 -0.001255 -0.010690 0.767119 0.889785 9.983483\n5884 6.463972 -0.002618 -0.002517 -0.010246 0.769784 0.869269 10.000690\n5885 6.469998 -0.002308 -0.003195 -0.010240 0.768770 0.874514 10.006704\n5886 6.476049 -0.002575 -0.004014 -0.009847 0.764823 0.900137 9.999419\n5887 6.482026 -0.002549 -0.003698 -0.009758 0.767025 0.899079 9.999746\n5888 6.488250 -0.002830 -0.002235 -0.010202 0.768347 0.895794 9.993183\n5889 6.494155 -0.003221 -0.001631 -0.010598 0.769503 0.907658 9.993976\n5890 6.500526 -0.003758 -0.001933 -0.011453 0.775888 0.911569 10.003041\n5891 6.506304 -0.003951 -0.002373 -0.011651 0.771822 0.890872 10.005397\n5892 6.512331 -0.004261 -0.002675 -0.011204 0.760911 0.876166 9.994857\n5893 6.518572 -0.004110 -0.002747 -0.010885 0.754249 0.896379 9.995467\n5894 6.524413 -0.003088 -0.002708 -0.010608 0.750770 0.924172 10.010674\n5895 6.530437 -0.003335 -0.002148 -0.010814 0.749037 0.916999 10.017381\n5896 6.536458 -0.003887 -0.000999 -0.011656 0.746358 0.895172 10.000219\n5897 6.542546 -0.003788 -0.000942 -0.012009 0.752229 0.893814 9.994895\n5898 6.548561 -0.003536 -0.001389 -0.011781 0.766886 0.883200 10.003464\n5899 6.554651 -0.003512 -0.002087 -0.011129 0.769098 0.878736 10.015478\n5900 6.560477 -0.003630 -0.002617 -0.009837 0.767352 0.881898 10.007539\n5901 6.566724 -0.003781 -0.002556 -0.009679 0.764654 0.885689 9.991748\n5902 6.572732 -0.003972 -0.002771 -0.010265 0.756411 0.877221 9.998652\n5903 6.578748 -0.003873 -0.002557 -0.010569 0.755411 0.871618 10.012266\n5904 6.584904 -0.003783 -0.002420 -0.010868 0.770029 0.886173 10.011693\n5905 6.590868 -0.003802 -0.002599 -0.011197 0.770638 0.889997 10.003514\n5906 6.596943 -0.003441 -0.002526 -0.011033 0.766510 0.866569 10.012714\n5907 6.603024 -0.003645 -0.002272 -0.010573 0.761340 0.853057 10.015245\n5908 6.609027 -0.003788 -0.002706 -0.010086 0.746252 0.880667 10.017648\n5909 6.615039 -0.003485 -0.003135 -0.010404 0.736027 0.900990 10.021690\n5910 6.621075 -0.003262 -0.003212 -0.011193 0.726836 0.895069 10.029448\n5911 6.627077 -0.003531 -0.003045 -0.011461 0.726886 0.890563 10.024199\n5912 6.633071 -0.003525 -0.002069 -0.011522 0.747248 0.895283 10.019393\n5913 6.639317 -0.003239 -0.001943 -0.011593 0.757041 0.894170 10.012570\n5914 6.645358 -0.003019 -0.002384 -0.011337 0.775434 0.871714 10.006314\n5915 6.651852 -0.002976 -0.002493 -0.010907 0.776101 0.871303 10.004972\n5916 6.657283 -0.002509 -0.002622 -0.010303 0.765447 0.885801 10.019379\n5917 6.663458 -0.002572 -0.002359 -0.010130 0.769062 0.894625 10.008492\n5918 6.669385 -0.003000 -0.001929 -0.010417 0.771067 0.907809 9.994007\n5919 6.675465 -0.003157 -0.001731 -0.010936 0.763987 0.908598 9.998674\n5920 6.681567 -0.003211 -0.001774 -0.011532 0.761511 0.910477 10.021968\n5921 6.687508 -0.003464 -0.002017 -0.011622 0.773190 0.897395 10.020509\n5922 6.693575 -0.003790 -0.002677 -0.011117 0.789894 0.874757 10.000771\n5923 6.700142 -0.003716 -0.002839 -0.010691 0.787619 0.880877 10.000521\n5924 6.705992 -0.003455 -0.002564 -0.010560 0.769742 0.888992 10.004708\n5925 6.712069 -0.003500 -0.002618 -0.010361 0.746467 0.867192 10.012864\n5926 6.717908 -0.003470 -0.002774 -0.010638 0.733677 0.870225 10.008225\n5927 6.724082 -0.003706 -0.002629 -0.011429 0.740825 0.886399 10.001042\n5928 6.729758 -0.003698 -0.002486 -0.011536 0.759176 0.883084 10.009982\n5929 6.736069 -0.003226 -0.002847 -0.010811 0.768282 0.869357 10.014140\n5930 6.741900 -0.002952 -0.003120 -0.010396 0.767754 0.874791 10.009509\n5931 6.748207 -0.002790 -0.002972 -0.009973 0.764529 0.883573 9.991459\n5932 6.753931 -0.002676 -0.002800 -0.009788 0.758270 0.880602 9.997618\n5933 6.760066 -0.003228 -0.002128 -0.010026 0.762411 0.882491 10.012765\n5934 6.766054 -0.003620 -0.002101 -0.010380 0.765311 0.892235 10.014077\n5935 6.772330 -0.003244 -0.002095 -0.010227 0.760897 0.892210 10.015167\n5936 6.778201 -0.003140 -0.002038 -0.010144 0.765268 0.880097 10.005092\n5937 6.784454 -0.003574 -0.002073 -0.010043 0.762018 0.879307 9.996936\n5938 6.790236 -0.003712 -0.002865 -0.010066 0.757353 0.891772 10.009445\n5939 6.796277 -0.003429 -0.003207 -0.010664 0.749023 0.881127 10.035854\n5940 6.802246 -0.003108 -0.002830 -0.010847 0.744985 0.881462 10.037678\n5941 6.808517 -0.003649 -0.001686 -0.011187 0.745131 0.896604 10.013582\n5942 6.814480 -0.004086 -0.001208 -0.011196 0.748985 0.896320 10.007593\n5943 6.820584 -0.004391 -0.000726 -0.011181 0.752228 0.894806 10.009054\n5944 6.826653 -0.004584 -0.001057 -0.010895 0.752170 0.893522 10.015032\n5945 6.832657 -0.004265 -0.001786 -0.010421 0.749300 0.900634 10.018614\n5946 6.838572 -0.004095 -0.002201 -0.010036 0.753751 0.904705 10.023942\n5947 6.844578 -0.003490 -0.003042 -0.010278 0.766074 0.898570 10.027450\n5948 6.850753 -0.003023 -0.002778 -0.010510 0.767036 0.897794 10.029154\n5949 6.857445 -0.003112 -0.002367 -0.011085 0.766326 0.904783 10.018205\n5950 6.862766 -0.002960 -0.002443 -0.011149 0.772877 0.900925 10.011766\n5951 6.868896 -0.002884 -0.002187 -0.011158 0.770098 0.862707 9.995467\n5952 6.874862 -0.002884 -0.002527 -0.010957 0.759833 0.852091 9.988256\n5953 6.880963 -0.002772 -0.003636 -0.010676 0.756173 0.873332 9.988708\n5954 6.886890 -0.002897 -0.003697 -0.010623 0.761214 0.882487 9.986402\n5955 6.893161 -0.003384 -0.002511 -0.010837 0.774405 0.885031 10.001437\n5956 6.899044 -0.003698 -0.001986 -0.010937 0.775141 0.890499 10.010386\n5957 6.905211 -0.003813 -0.001170 -0.011220 0.756992 0.882284 10.016767\n5958 6.911321 -0.003523 -0.000990 -0.011287 0.753499 0.873510 10.015330\n5959 6.917419 -0.003447 -0.001330 -0.010621 0.755843 0.857066 10.014423\n5960 6.923261 -0.003669 -0.001694 -0.010247 0.761245 0.871810 10.005078\n5961 6.929296 -0.003827 -0.002540 -0.010128 0.758438 0.894684 9.998430\n5962 6.935284 -0.003858 -0.002885 -0.010110 0.761415 0.893946 9.998582\n5963 6.941228 -0.004355 -0.003338 -0.010586 0.751866 0.896580 10.013293\n5964 6.947311 -0.004632 -0.003165 -0.011055 0.745322 0.897304 10.012960\n5965 6.953378 -0.004360 -0.002267 -0.011616 0.758975 0.873519 10.007136\n5966 6.959373 -0.004131 -0.002127 -0.011361 0.772945 0.858185 10.005197\n5967 6.965421 -0.003669 -0.002750 -0.009979 0.768604 0.868820 9.995364\n5968 6.971420 -0.003675 -0.003124 -0.009263 0.763162 0.885297 9.993335\n5969 6.977587 -0.003906 -0.003443 -0.009442 0.761212 0.889374 10.006974\n5970 6.983558 -0.003725 -0.003249 -0.010155 0.755325 0.885324 10.014688\n5971 6.989612 -0.003003 -0.001631 -0.010881 0.745790 0.905730 10.019174\n5972 6.995582 -0.002866 -0.001334 -0.010900 0.749325 0.910134 10.012704\n5973 7.001752 -0.002476 -0.001873 -0.010802 0.745957 0.884689 10.017077\n5974 7.007797 -0.002721 -0.001935 -0.010705 0.747423 0.874146 10.026755\n5975 7.014063 -0.003622 -0.001812 -0.010724 0.761601 0.884368 10.009294\n5976 7.019806 -0.003606 -0.001925 -0.010600 0.762240 0.895525 9.998276\n5977 7.025807 -0.003193 -0.001923 -0.010244 0.769670 0.891867 9.996767\n5978 7.031916 -0.003024 -0.002086 -0.010442 0.767764 0.888869 9.998018\n5979 7.037978 -0.002815 -0.002022 -0.011088 0.765758 0.899849 9.997329\n5980 7.044621 -0.002930 -0.001868 -0.011081 0.763613 0.894897 10.000556\n5981 7.050217 -0.004197 -0.001568 -0.011435 0.762403 0.867880 9.998253\n5982 7.056449 -0.004857 -0.002584 -0.011142 0.782539 0.875991 9.980393\n5983 7.062017 -0.004438 -0.003071 -0.010575 0.780591 0.892429 9.977715\n5984 7.068689 -0.003321 -0.003076 -0.010774 0.767374 0.885213 9.990289\n5985 7.074227 -0.003711 -0.002901 -0.010975 0.767843 0.887105 9.996019\n5986 7.080759 -0.004014 -0.002800 -0.011063 0.765815 0.899502 10.001429\n5987 7.086367 -0.003683 -0.002818 -0.010305 0.769058 0.923103 10.011684\n5988 7.092654 -0.004609 -0.002827 -0.010142 0.779179 0.890750 10.018661\n5989 7.098344 -0.004906 -0.002616 -0.010034 0.772980 0.872828 9.994594\n5990 7.104672 -0.004227 -0.002109 -0.009585 0.781531 0.877290 9.967752\n5991 7.110521 -0.003834 -0.001750 -0.009880 0.776246 0.889627 9.975736\n5992 7.117188 -0.004285 -0.001699 -0.011158 0.756983 0.895713 9.997229\n5993 7.122774 -0.004318 -0.001455 -0.011682 0.747062 0.903830 10.014031\n5994 7.128784 -0.004151 -0.001746 -0.011485 0.754232 0.926301 10.028632\n5995 7.134667 -0.004177 -0.001775 -0.011277 0.765776 0.916341 10.027564\n5996 7.140887 -0.004343 -0.001342 -0.010875 0.774015 0.873203 10.033626\n5997 7.146770 -0.004136 -0.001679 -0.010697 0.776072 0.865309 10.015910\n5998 7.152973 -0.003414 -0.002334 -0.010359 0.771237 0.873057 9.985851\n5999 7.158776 -0.003392 -0.002738 -0.010564 0.758053 0.877144 9.982441\n6000 7.165013 -0.003766 -0.002563 -0.010747 0.747004 0.888803 9.991578\n6001 7.170938 -0.003980 -0.002234 -0.010823 0.753339 0.899531 9.990443\n6002 7.177020 -0.003805 -0.002048 -0.011057 0.765591 0.909840 10.010736\n6003 7.182966 -0.003444 -0.002131 -0.010904 0.771855 0.894874 10.024556\n6004 7.189226 -0.003268 -0.002295 -0.010566 0.776467 0.878148 10.034890\n6005 7.194932 -0.003242 -0.002368 -0.010424 0.770701 0.888755 10.028203\n6006 7.201264 -0.003615 -0.002331 -0.010140 0.756767 0.902554 10.020508\n6007 7.207253 -0.003794 -0.002260 -0.010246 0.745133 0.900011 10.017548\n6008 7.213282 -0.003921 -0.001888 -0.010698 0.752792 0.897620 10.005780\n6009 7.219394 -0.003806 -0.001942 -0.010726 0.769907 0.899219 10.001847\n6010 7.225290 -0.003508 -0.002223 -0.010657 0.779649 0.890759 9.987699\n6011 7.231407 -0.003400 -0.002268 -0.010428 0.780079 0.874949 9.986166\n6012 7.237360 -0.003287 -0.002444 -0.010122 0.767193 0.850577 9.988503\n6013 7.243643 -0.003472 -0.002850 -0.010513 0.761178 0.864438 9.990610\n6014 7.249492 -0.003479 -0.003227 -0.010848 0.768238 0.876897 10.002714\n6015 7.255543 -0.003355 -0.003193 -0.010876 0.770911 0.873654 9.995565\n6016 7.261431 -0.003115 -0.003314 -0.010645 0.776959 0.884258 10.007926\n6017 7.267529 -0.003367 -0.003367 -0.010419 0.782823 0.890867 10.020720\n6018 7.273586 -0.003447 -0.003312 -0.010659 0.779396 0.883664 10.033908\n6019 7.279582 -0.003584 -0.003433 -0.010688 0.773648 0.878233 10.021735\n6020 7.285731 -0.003758 -0.003527 -0.010120 0.771575 0.884239 9.978072\n6021 7.291784 -0.003587 -0.002881 -0.009556 0.773514 0.886759 9.971438\n6022 7.297872 -0.002837 -0.002013 -0.009413 0.753608 0.895258 9.969664\n6023 7.303787 -0.003026 -0.001587 -0.009915 0.749364 0.899635 9.972080\n6024 7.309915 -0.003770 -0.001238 -0.011014 0.748768 0.911504 9.973503\n6025 7.315997 -0.004361 -0.001246 -0.011645 0.749796 0.909371 9.979811\n6026 7.322147 -0.004246 -0.000694 -0.011880 0.759968 0.879252 10.004333\n6027 7.327914 -0.004218 -0.001143 -0.011593 0.768198 0.867699 10.011902\n6028 7.333996 -0.003874 -0.002905 -0.010765 0.770801 0.887306 10.023371\n6029 7.340000 -0.003680 -0.003396 -0.010368 0.773011 0.893351 10.018001\n6030 7.346020 -0.003802 -0.003212 -0.010336 0.760909 0.893332 10.011971\n6031 7.352063 -0.004034 -0.003197 -0.010454 0.753077 0.903201 10.010319\n6032 7.358087 -0.004185 -0.002464 -0.011057 0.745548 0.920390 10.010588\n6033 7.364357 -0.004280 -0.001871 -0.011329 0.741834 0.903422 10.013045\n6034 7.370212 -0.004225 -0.001551 -0.010878 0.763858 0.868945 10.003684\n6035 7.376207 -0.004098 -0.001977 -0.010434 0.769882 0.882824 9.989970\n6036 7.382331 -0.003387 -0.002383 -0.009224 0.756236 0.915009 9.992796\n6037 7.388294 -0.003164 -0.002318 -0.009271 0.751037 0.911443 10.002676\n6038 7.394326 -0.003657 -0.001819 -0.010775 0.753178 0.898256 10.006968\n6039 7.400332 -0.003814 -0.001845 -0.011312 0.752846 0.900812 10.002613\n6040 7.406548 -0.003968 -0.001403 -0.011192 0.758806 0.883192 10.007473\n6041 7.412575 -0.003996 -0.001607 -0.011004 0.766697 0.860694 10.013825\n6042 7.418597 -0.003997 -0.003365 -0.010523 0.786588 0.850294 10.007384\n6043 7.424711 -0.003818 -0.003396 -0.010176 0.793096 0.863666 10.006358\n6044 7.430725 -0.003546 -0.002787 -0.009600 0.773576 0.879027 10.005215\n6045 7.436699 -0.003594 -0.002819 -0.009785 0.761691 0.886614 9.995511\n6046 7.442714 -0.003430 -0.002030 -0.010652 0.753889 0.918370 9.989417\n6047 7.448789 -0.003552 -0.001583 -0.010997 0.755461 0.923848 9.987202\n6048 7.454912 -0.003650 -0.001118 -0.011456 0.756896 0.880979 9.999212\n6049 7.460969 -0.003659 -0.000913 -0.011710 0.754174 0.860274 9.997071\n6050 7.466916 -0.003631 -0.001098 -0.010908 0.738299 0.880064 9.984240\n6051 7.473485 -0.003403 -0.001398 -0.010345 0.739028 0.897065 9.978766\n6052 7.478959 -0.003297 -0.002049 -0.009453 0.758951 0.889735 9.996964\n6053 7.485546 -0.002913 -0.002199 -0.009602 0.762008 0.897061 10.020991\n6054 7.491157 -0.002969 -0.002054 -0.010222 0.758976 0.914958 10.021941\n6055 7.497620 -0.003276 -0.001904 -0.010905 0.757234 0.915774 10.009136\n6056 7.503184 -0.003897 -0.001752 -0.011815 0.764795 0.890084 9.994486\n6057 7.509723 -0.003776 -0.001580 -0.011198 0.771350 0.903589 9.988197\n6058 7.515323 -0.003377 -0.001519 -0.010449 0.764795 0.903621 9.985582\n6059 7.521864 -0.003296 -0.001290 -0.010187 0.755359 0.876807 9.995640\n6060 7.527663 -0.003579 -0.001139 -0.010695 0.753047 0.874140 10.000296\n6061 7.533944 -0.004792 -0.001461 -0.011316 0.756746 0.906497 9.997533\n6062 7.539433 -0.004962 -0.001569 -0.011557 0.757598 0.912972 9.995034\n6063 7.545805 -0.004482 -0.001737 -0.011272 0.761099 0.892667 9.998329\n6064 7.551588 -0.004211 -0.001816 -0.010909 0.761999 0.889148 10.010518\n6065 7.557888 -0.003545 -0.002284 -0.010428 0.749750 0.882124 10.034432\n6066 7.563541 -0.003374 -0.002679 -0.010128 0.745366 0.875176 10.035951\n6067 7.569820 -0.003348 -0.003280 -0.010082 0.749235 0.878211 10.030316\n6068 7.575622 -0.003739 -0.003067 -0.010122 0.756806 0.888502 10.022892\n6069 7.582079 -0.003595 -0.002571 -0.010112 0.764564 0.902624 10.008374\n6070 7.587648 -0.003353 -0.002138 -0.010303 0.762171 0.899815 10.002360\n6071 7.593890 -0.003801 -0.001742 -0.010913 0.767086 0.871884 9.993104\n6072 7.599680 -0.004062 -0.002145 -0.010891 0.771523 0.878037 9.995093\n6073 7.605847 -0.003666 -0.002604 -0.010710 0.770621 0.912250 9.997307\n6074 7.611831 -0.003408 -0.002537 -0.010573 0.772065 0.909282 10.003368\n6075 7.618010 -0.003507 -0.002137 -0.010109 0.759662 0.902287 10.005816\n6076 7.624005 -0.003732 -0.001889 -0.010203 0.752613 0.908528 10.001565\n6077 7.630326 -0.003994 -0.000870 -0.011262 0.755554 0.924483 9.992916\n6078 7.635951 -0.004084 -0.000615 -0.011986 0.763448 0.913447 10.001176\n6079 7.642132 -0.003523 -0.001138 -0.011456 0.762439 0.883512 10.005120\n6080 7.648197 -0.003501 -0.001513 -0.010883 0.760416 0.880819 10.003425\n6081 7.654180 -0.003721 -0.002625 -0.010297 0.762377 0.891269 10.013274\n6082 7.660257 -0.003532 -0.002894 -0.010131 0.765535 0.877186 10.014089\n6083 7.666223 -0.003624 -0.002725 -0.010485 0.767664 0.853954 9.996765\n6084 7.672262 -0.003396 -0.002768 -0.011045 0.766980 0.871019 9.987322\n6085 7.678262 -0.002899 -0.003155 -0.011774 0.769758 0.889920 9.994000\n6086 7.684330 -0.003601 -0.002986 -0.011808 0.767679 0.875180 10.000118\n6087 7.690312 -0.003695 -0.002735 -0.011202 0.760983 0.862405 10.016793\n6088 7.696380 -0.003671 -0.002929 -0.010583 0.753911 0.878278 10.017378\n6089 7.702602 -0.003583 -0.002835 -0.009441 0.746588 0.885464 9.995737\n6090 7.708570 -0.003359 -0.002533 -0.009349 0.755789 0.876535 9.979292\n6091 7.714654 -0.003498 -0.002853 -0.009462 0.776655 0.894248 9.998835\n6092 7.720527 -0.003729 -0.003130 -0.009762 0.777377 0.899642 10.017415\n6093 7.726907 -0.003835 -0.002619 -0.010556 0.773464 0.874856 10.025349\n6094 7.733048 -0.003972 -0.002407 -0.010974 0.775160 0.865074 10.028220\n6095 7.738727 -0.003832 -0.002154 -0.010828 0.763825 0.882890 10.026069\n6096 7.744700 -0.003535 -0.001885 -0.010508 0.754159 0.890571 10.026569\n6097 7.750839 -0.003666 -0.001380 -0.010108 0.743452 0.883670 10.012506\n6098 7.756846 -0.003577 -0.001279 -0.010178 0.743305 0.887556 9.998728\n6099 7.762794 -0.003439 -0.001839 -0.010491 0.745412 0.914829 9.986362\n6100 7.768914 -0.003572 -0.002070 -0.010617 0.740530 0.918368 9.992629\n6101 7.774984 -0.003989 -0.001853 -0.010953 0.752690 0.869751 10.003137\n6102 7.780999 -0.004049 -0.001571 -0.010759 0.766371 0.857378 10.007457\n6103 7.786973 -0.004006 -0.002096 -0.010412 0.784738 0.874091 10.004332\n6104 7.793166 -0.003859 -0.002407 -0.010414 0.790745 0.882245 10.003951\n6105 7.799166 -0.003890 -0.002467 -0.010342 0.781032 0.882656 10.030254\n6106 7.805057 -0.004034 -0.002411 -0.010535 0.772764 0.885332 10.034350\n6107 7.811186 -0.003995 -0.002145 -0.011464 0.755484 0.886088 10.014271\n6108 7.817057 -0.003791 -0.002165 -0.011823 0.753613 0.879158 10.000731\n6109 7.823327 -0.003879 -0.002629 -0.011572 0.755806 0.872185 9.987366\n6110 7.829309 -0.003898 -0.002477 -0.011019 0.754034 0.876251 9.993806\n6111 7.835568 -0.003704 -0.002152 -0.009429 0.762478 0.884960 10.011582\n6112 7.841405 -0.004081 -0.001923 -0.009494 0.780928 0.881202 10.026407\n6113 7.847576 -0.003648 -0.002225 -0.010456 0.785511 0.894421 10.012999\n6114 7.853507 -0.003238 -0.002399 -0.010959 0.769694 0.907606 10.006510\n6115 7.859711 -0.002898 -0.002071 -0.010919 0.759539 0.913799 10.019970\n6116 7.865576 -0.003191 -0.001728 -0.010807 0.756365 0.898772 10.035187\n6117 7.871668 -0.004474 -0.001704 -0.011275 0.752964 0.876922 10.044462\n6118 7.877779 -0.004642 -0.001720 -0.011329 0.755113 0.878319 10.033741\n6119 7.883707 -0.004128 -0.001597 -0.010521 0.756659 0.873267 10.020128\n6120 7.889796 -0.003823 -0.001847 -0.010250 0.762193 0.880967 10.015245\n6121 7.895818 -0.003487 -0.002215 -0.010830 0.761369 0.915847 9.999022\n6122 7.901930 -0.003513 -0.002084 -0.011227 0.764796 0.927896 9.993753\n6123 7.907894 -0.003213 -0.001970 -0.011438 0.770431 0.898874 10.020341\n6124 7.913910 -0.003439 -0.001492 -0.011382 0.770966 0.879423 10.034338\n6125 7.919916 -0.004254 -0.001442 -0.011342 0.763563 0.875151 10.010746\n6126 7.926524 -0.004495 -0.001448 -0.010873 0.761002 0.883013 10.011787\n6127 7.932022 -0.004019 -0.001688 -0.010319 0.768618 0.885460 10.011343\n6128 7.939027 -0.003704 -0.001783 -0.009529 0.763406 0.892571 9.989720\n6129 7.945158 -0.003594 -0.001624 -0.009878 0.759660 0.898828 9.986353\n6130 7.951333 -0.003052 -0.001768 -0.010255 0.757973 0.895974 10.002449\n6131 7.957219 -0.003175 -0.002288 -0.010363 0.763994 0.886804 10.004943\n6132 7.963285 -0.003859 -0.002268 -0.011155 0.773870 0.898640 10.012224\n6133 7.969270 -0.004030 -0.002213 -0.011223 0.771079 0.907593 10.026858\n6134 7.975537 -0.003900 -0.001934 -0.010825 0.763514 0.879841 10.026154\n6135 7.981541 -0.003846 -0.001607 -0.010671 0.763552 0.868167 10.026857\n6136 7.987433 -0.003574 -0.001601 -0.010699 0.752398 0.892952 10.026022\n6137 7.993494 -0.003642 -0.001719 -0.010751 0.746299 0.906945 10.020708\n6138 7.999495 -0.003581 -0.001899 -0.010592 0.739934 0.897109 10.022458\n6139 8.005581 -0.003999 -0.002114 -0.010174 0.738083 0.882211 10.020489\n6140 8.011524 -0.004606 -0.002393 -0.010327 0.750736 0.886322 10.001574\n6141 8.017654 -0.004789 -0.002397 -0.010561 0.755966 0.893620 10.011725\n6142 8.023688 -0.004501 -0.001842 -0.010382 0.754314 0.896520 10.033795\n6143 8.029683 -0.004231 -0.001771 -0.010108 0.752633 0.894001 10.021823\n6144 8.035702 -0.004057 -0.001571 -0.010193 0.739938 0.902932 10.003276\n6145 8.041930 -0.004125 -0.001353 -0.010254 0.741356 0.901362 10.002272\n6146 8.048083 -0.004074 -0.001574 -0.010164 0.758081 0.872672 10.008798\n6147 8.053818 -0.003805 -0.001502 -0.010245 0.761807 0.868248 10.008525\n6148 8.059841 -0.003112 -0.001665 -0.010511 0.758484 0.876730 10.003882\n6149 8.066004 -0.002742 -0.001857 -0.010345 0.751344 0.872759 9.995744\n6150 8.072369 -0.003431 -0.002085 -0.009740 0.742451 0.882025 9.988731\n6151 8.078056 -0.003817 -0.001647 -0.009736 0.743635 0.909079 9.991435\n6152 8.084085 -0.003328 -0.000656 -0.010831 0.742260 0.913755 10.002241\n6153 8.090039 -0.003211 -0.000765 -0.011371 0.743201 0.887849 10.013925\n6154 8.096116 -0.003589 -0.001919 -0.011685 0.758300 0.876985 9.994609\n6155 8.102287 -0.003776 -0.002297 -0.011414 0.763010 0.883553 9.982638\n6156 8.108262 -0.003740 -0.003396 -0.009942 0.750530 0.876907 9.985229\n6157 8.114835 -0.003839 -0.003530 -0.009502 0.750077 0.866070 9.990950\n6158 8.120360 -0.004036 -0.002797 -0.009584 0.758454 0.867940 10.001221\n6159 8.126831 -0.003883 -0.002770 -0.009871 0.758468 0.883295 10.004151\n6160 8.132531 -0.003887 -0.002754 -0.010890 0.763394 0.929522 10.005279\n6161 8.138836 -0.003760 -0.002256 -0.011226 0.762464 0.936015 10.014359\n6162 8.144462 -0.003645 -0.002178 -0.011200 0.755687 0.917107 10.007504\n6163 8.151126 -0.003450 -0.001853 -0.011310 0.757585 0.862058 9.997741\n6164 8.156551 -0.003456 -0.001869 -0.011314 0.760302 0.843319 10.006035\n6165 8.163038 -0.002944 -0.002021 -0.010581 0.768721 0.868368 10.027538\n6166 8.168647 -0.002956 -0.001742 -0.010084 0.774376 0.895808 10.029754\n6167 8.175025 -0.003097 -0.000793 -0.009451 0.754734 0.912060 10.023411\n6168 8.180880 -0.003032 -0.000809 -0.009658 0.757087 0.901202 10.024630\n6169 8.187116 -0.003164 -0.001395 -0.011273 0.769863 0.884906 10.015982\n6170 8.193080 -0.003245 -0.001980 -0.011790 0.774082 0.898074 10.021123\n6171 8.199112 -0.003697 -0.003027 -0.012283 0.770890 0.912220 10.020442\n6172 8.204911 -0.003527 -0.003314 -0.011698 0.768725 0.901517 10.020918\n6173 8.211058 -0.002908 -0.002917 -0.009968 0.766600 0.879516 10.005188\n6174 8.217103 -0.002663 -0.002297 -0.009803 0.762629 0.891760 9.989207\n6175 8.223106 -0.002443 -0.001502 -0.011069 0.757147 0.910276 9.989114\n6176 8.229093 -0.002974 -0.001412 -0.011268 0.764614 0.916403 10.000843\n6177 8.235167 -0.004063 -0.002189 -0.010511 0.767269 0.921866 10.001957\n6178 8.241142 -0.004155 -0.002416 -0.009991 0.764669 0.906835 10.001195\n6179 8.247441 -0.004583 -0.001831 -0.009928 0.756595 0.859051 9.996243\n6180 8.253296 -0.004601 -0.001505 -0.010508 0.755047 0.852497 10.001904\n6181 8.259182 -0.004111 -0.001283 -0.011264 0.750807 0.889451 10.005529\n6182 8.265392 -0.003992 -0.001210 -0.011085 0.748504 0.907491 10.007328\n6183 8.271318 -0.003939 -0.001024 -0.010779 0.745329 0.895298 10.003107\n6184 8.277278 -0.004028 -0.001224 -0.011034 0.748951 0.876541 10.009720\n6185 8.283647 -0.003388 -0.001873 -0.011778 0.755850 0.864575 10.016008\n6186 8.289452 -0.003107 -0.002516 -0.011538 0.759551 0.871305 10.020389\n6187 8.295565 -0.003203 -0.003161 -0.010998 0.762306 0.895358 10.028984\n6188 8.301559 -0.003044 -0.002933 -0.010620 0.758943 0.895698 10.027494\n6189 8.307552 -0.003500 -0.002979 -0.009941 0.754069 0.891684 10.004906\n6190 8.313801 -0.003506 -0.003303 -0.009870 0.747432 0.887460 10.008106\n6191 8.319640 -0.003242 -0.003618 -0.010790 0.756419 0.880012 10.013837\n6192 8.325677 -0.003245 -0.003914 -0.010970 0.766015 0.894141 10.015076\n6193 8.331626 -0.003538 -0.003996 -0.010632 0.764958 0.915064 9.986875\n6194 8.337778 -0.003399 -0.003696 -0.010274 0.758150 0.902416 9.981856\n6195 8.343969 -0.003337 -0.002271 -0.010200 0.745137 0.872541 9.973871\n6196 8.349845 -0.003500 -0.001777 -0.010614 0.743833 0.877437 9.983644\n6197 8.355970 -0.003769 -0.001178 -0.011328 0.744837 0.899062 10.017202\n6198 8.361908 -0.003923 -0.000680 -0.011255 0.752656 0.897207 10.042286\n6199 8.368000 -0.004019 0.000241 -0.010747 0.773725 0.890891 10.041008\n6200 8.374029 -0.004017 0.000585 -0.010749 0.778554 0.890287 10.034042\n6201 8.380144 -0.003903 -0.000092 -0.010801 0.777627 0.900067 10.016140\n6202 8.386078 -0.003666 -0.000992 -0.011050 0.768653 0.889841 10.007771\n6203 8.392164 -0.004380 -0.002210 -0.010671 0.750611 0.897162 10.029704\n6204 8.398224 -0.004554 -0.002411 -0.010320 0.740383 0.920210 10.031777\n6205 8.404256 -0.003907 -0.002442 -0.009924 0.746246 0.906657 10.012007\n6206 8.410210 -0.003850 -0.002641 -0.010287 0.758690 0.883729 9.999147\n6207 8.416297 -0.003652 -0.003337 -0.010999 0.774684 0.877649 10.009384\n6208 8.422394 -0.003396 -0.003618 -0.011154 0.772974 0.886005 10.022390\n6209 8.428234 -0.003112 -0.003536 -0.010435 0.763621 0.883624 10.017249\n6210 8.434365 -0.003313 -0.003162 -0.009968 0.762546 0.874373 10.022369\n6211 8.440456 -0.003932 -0.002441 -0.010209 0.767853 0.869917 10.008844\n6212 8.446585 -0.004259 -0.001666 -0.010280 0.768287 0.869448 9.995940\n6213 8.452505 -0.004492 -0.000942 -0.010312 0.760176 0.877029 10.011827\n6214 8.458491 -0.004485 -0.000688 -0.010430 0.756909 0.893816 10.015389\n6215 8.464700 -0.003716 -0.000967 -0.010763 0.746968 0.918164 10.010706\n6216 8.470664 -0.003364 -0.001133 -0.010833 0.746341 0.910125 10.001862\n6217 8.476710 -0.003377 -0.001935 -0.010546 0.751113 0.879589 10.010930\n6218 8.482590 -0.003627 -0.002307 -0.010106 0.751496 0.878712 10.017670\n6219 8.488757 -0.003889 -0.001771 -0.010164 0.755953 0.888187 10.019822\n6220 8.494861 -0.003992 -0.001518 -0.010321 0.754546 0.892312 10.014751\n6221 8.500851 -0.003672 -0.002463 -0.010256 0.759387 0.890170 9.998751\n6222 8.505813 -0.003779 -0.002738 -0.010556 0.764898 0.896795 9.992670\n6223 8.511949 -0.004451 -0.002976 -0.011232 0.783620 0.913435 10.002568\n6224 8.518032 -0.004143 -0.003034 -0.011111 0.787070 0.905324 10.012647\n6225 8.524134 -0.004085 -0.003173 -0.011333 0.777922 0.892036 10.025496\n6226 8.530175 -0.004112 -0.002952 -0.011509 0.772993 0.900470 10.026011\n6227 8.536282 -0.003733 -0.002606 -0.011432 0.755384 0.894961 10.005752\n6228 8.542098 -0.003470 -0.002308 -0.011322 0.755677 0.883046 10.007899\n6229 8.548475 -0.004612 -0.002046 -0.010762 0.761254 0.875016 9.998017\n6230 8.554360 -0.004991 -0.002104 -0.010486 0.758027 0.881962 10.005686\n6231 8.560267 -0.004206 -0.001780 -0.010093 0.756403 0.880707 10.031917\n6232 8.566310 -0.003617 -0.001679 -0.009971 0.762749 0.875189 10.030384\n6233 8.572341 -0.003938 -0.001522 -0.010449 0.757245 0.880763 10.012537\n6234 8.578504 -0.003962 -0.001457 -0.010702 0.751374 0.891374 10.014812\n6235 8.584512 -0.003087 -0.001339 -0.011221 0.740942 0.894031 10.007464\n6236 8.590757 -0.002896 -0.001478 -0.011106 0.746862 0.883102 10.008147\n6237 8.596488 -0.003683 -0.002391 -0.010786 0.769951 0.899643 10.009953\n6238 8.602552 -0.003696 -0.002860 -0.010578 0.768690 0.911685 10.019359\n6239 8.608515 -0.002991 -0.003361 -0.010371 0.764399 0.897027 10.012071\n6240 8.614615 -0.002606 -0.003197 -0.010464 0.765223 0.886140 10.011455\n6241 8.620515 -0.003219 -0.002992 -0.010513 0.774327 0.897194 10.015194\n6242 8.626775 -0.003116 -0.002737 -0.010698 0.773217 0.903168 10.018522\n6243 8.632644 -0.002900 -0.002527 -0.011065 0.765839 0.881910 10.012877\n6244 8.638676 -0.003096 -0.002386 -0.011097 0.760803 0.874751 10.013171\n6245 8.644713 -0.004030 -0.001357 -0.010587 0.768423 0.883764 10.011134\n6246 8.650898 -0.004108 -0.001314 -0.010758 0.765924 0.880288 10.003585\n6247 8.657327 -0.003805 -0.001110 -0.010628 0.762413 0.860460 9.995160\n6248 8.662904 -0.003755 -0.000908 -0.010263 0.762344 0.864082 9.993947\n6249 8.669032 -0.003627 -0.000976 -0.009505 0.762272 0.884080 9.997023\n6250 8.674909 -0.003425 -0.001353 -0.009729 0.764254 0.886250 10.001079\n6251 8.680993 -0.003712 -0.001677 -0.010318 0.766690 0.875969 10.008780\n6252 8.687032 -0.003828 -0.001662 -0.010415 0.772384 0.876371 10.012569\n6253 8.693252 -0.003180 -0.002327 -0.010685 0.765676 0.889549 10.020120\n6254 8.699226 -0.003097 -0.002792 -0.010852 0.756873 0.885108 10.020011\n6255 8.705240 -0.003298 -0.002808 -0.010355 0.755375 0.876426 10.019543\n6256 8.711370 -0.003184 -0.002636 -0.009997 0.767245 0.884717 10.015362\n6257 8.717414 -0.002704 -0.002128 -0.009614 0.784265 0.896297 10.019309\n6258 8.724245 -0.002470 -0.001818 -0.009771 0.792501 0.895232 10.030910\n6259 8.729505 -0.002766 -0.002133 -0.010293 0.784853 0.906148 10.019783\n6260 8.735543 -0.003283 -0.002622 -0.010347 0.779307 0.912743 10.009065\n6261 8.741600 -0.004313 -0.002710 -0.010520 0.773110 0.903812 9.994196\n6262 8.747430 -0.004722 -0.002546 -0.010816 0.769034 0.890022 9.993093\n6263 8.753432 -0.004165 -0.002091 -0.011232 0.760434 0.882841 10.010555\n6264 8.760260 -0.003276 -0.001561 -0.010400 0.760146 0.911398 10.014840\n6265 8.765796 -0.003106 -0.001328 -0.009950 0.764321 0.911428 10.007561\n6266 8.772328 -0.004176 -0.001811 -0.009498 0.764779 0.886684 9.997910\n6267 8.777842 -0.004618 -0.001898 -0.009650 0.764088 0.888641 10.003224\n6268 8.784372 -0.004952 -0.002172 -0.010381 0.752741 0.883622 9.998638\n6269 8.790031 -0.004578 -0.002355 -0.010491 0.751540 0.874624 9.999593\n6270 8.796389 -0.004103 -0.001709 -0.010065 0.760322 0.878462 10.013220\n6271 8.801996 -0.004063 -0.001573 -0.010153 0.767320 0.891122 10.020744\n6272 8.808400 -0.003597 -0.001983 -0.010065 0.767987 0.892974 10.028112\n6273 8.814000 -0.003565 -0.002137 -0.010072 0.770365 0.874187 10.032742\n6274 8.820388 -0.004439 -0.002227 -0.010290 0.778833 0.885201 10.017920\n6275 8.826159 -0.004767 -0.001955 -0.010348 0.769793 0.900298 10.007188\n6276 8.832494 -0.004186 -0.002579 -0.010373 0.755745 0.896229 10.012543\n6277 8.838254 -0.004283 -0.002710 -0.010332 0.760291 0.879771 10.021480\n6278 8.844496 -0.003911 -0.002916 -0.009999 0.762459 0.878964 10.039410\n6279 8.850249 -0.003457 -0.002806 -0.010025 0.762777 0.893788 10.035608\n6280 8.856592 -0.003450 -0.002538 -0.010647 0.763535 0.904318 10.028477\n6281 8.862583 -0.003983 -0.002507 -0.010835 0.773395 0.900740 10.021127\n6282 8.868568 -0.003758 -0.002644 -0.010528 0.780496 0.907138 10.007445\n6283 8.874267 -0.003356 -0.002518 -0.010525 0.779052 0.910273 10.005458\n6284 8.880376 -0.003528 -0.001911 -0.010700 0.775749 0.883723 10.008137\n6285 8.886544 -0.004121 -0.001959 -0.010763 0.778601 0.872532 10.018476\n6286 8.892530 -0.004286 -0.002224 -0.010855 0.772131 0.876132 10.020953\n6287 8.898580 -0.004021 -0.002301 -0.010872 0.766155 0.875526 10.010140\n6288 8.904653 -0.004139 -0.001968 -0.010558 0.765083 0.886343 10.004289\n6289 8.910750 -0.004376 -0.001360 -0.010193 0.760732 0.897462 10.011801\n6290 8.916654 -0.003997 -0.001040 -0.010278 0.762808 0.904265 10.017356\n6291 8.922900 -0.003604 -0.001310 -0.010530 0.760598 0.898289 10.014228\n6292 8.928992 -0.003536 -0.001763 -0.011352 0.758917 0.868970 10.003944\n6293 8.934693 -0.003678 -0.002050 -0.011343 0.757544 0.864567 10.003772\n6294 8.940776 -0.003628 -0.001988 -0.010839 0.757189 0.894576 10.013371\n6295 8.946771 -0.003539 -0.001596 -0.010677 0.752133 0.892733 10.014054\n6296 8.952856 -0.003811 -0.001741 -0.010835 0.752589 0.888674 10.017756\n6297 8.958824 -0.003964 -0.002405 -0.010923 0.758533 0.896258 10.021955\n6298 8.965328 -0.004010 -0.002794 -0.010814 0.761845 0.909431 10.032181\n6299 8.971006 -0.003743 -0.002990 -0.010929 0.761877 0.909040 10.029649\n6300 8.977133 -0.003805 -0.002583 -0.010420 0.759562 0.902536 10.000115\n6301 8.983146 -0.003794 -0.002563 -0.010186 0.758109 0.906471 9.994398\n6302 8.989375 -0.003479 -0.002541 -0.010192 0.757640 0.904052 9.998477\n6303 8.995272 -0.003058 -0.002472 -0.010456 0.761880 0.887600 10.003491\n6304 9.001376 -0.002825 -0.002346 -0.011176 0.774776 0.870444 9.987788\n6305 9.007332 -0.003014 -0.002321 -0.011232 0.776577 0.881352 9.971607\n6306 9.013310 -0.003739 -0.001886 -0.010819 0.772160 0.898592 9.972515\n6307 9.019444 -0.004143 -0.001467 -0.010661 0.766802 0.887388 9.971539\n6308 9.025360 -0.004140 -0.001023 -0.010372 0.760055 0.881572 9.981160\n6309 9.031646 -0.004023 -0.001168 -0.010309 0.761758 0.889917 9.994798\n6310 9.037505 -0.003287 -0.001678 -0.009961 0.756072 0.886682 10.006444\n6311 9.043646 -0.002993 -0.001631 -0.010199 0.754973 0.882089 10.002595\n6312 9.049631 -0.003307 -0.001547 -0.010668 0.762115 0.893102 9.996667\n6313 9.055663 -0.003775 -0.001570 -0.010794 0.755105 0.904447 9.995957\n6314 9.061643 -0.004621 -0.001890 -0.011182 0.752612 0.902521 10.010566\n6315 9.067795 -0.004772 -0.002123 -0.011068 0.745138 0.895558 10.022550\n6316 9.073800 -0.004423 -0.002343 -0.010802 0.745452 0.893669 10.012077\n6317 9.079641 -0.003962 -0.002363 -0.010704 0.756664 0.892389 10.008603\n6318 9.085749 -0.004143 -0.002347 -0.010682 0.776653 0.876425 10.025084\n6319 9.091896 -0.004566 -0.002337 -0.010675 0.780994 0.878854 10.018291\n6320 9.097788 -0.004390 -0.002017 -0.010784 0.775777 0.904963 9.990137\n6321 9.103952 -0.004090 -0.001820 -0.010950 0.771632 0.916307 10.007973\n6322 9.109805 -0.004197 -0.000938 -0.011242 0.770712 0.896614 10.038814\n6323 9.115915 -0.004649 -0.000614 -0.011052 0.764473 0.883728 10.042713\n6324 9.122158 -0.004581 -0.000392 -0.010477 0.758633 0.880450 10.037090\n6325 9.128184 -0.003836 -0.000678 -0.010462 0.761527 0.880471 10.032562\n6326 9.134089 -0.003063 -0.001599 -0.010396 0.761934 0.868320 10.044992\n6327 9.140321 -0.002889 -0.002316 -0.010414 0.755026 0.876530 10.044813\n6328 9.146401 -0.002857 -0.002097 -0.010541 0.756701 0.904393 10.024426\n6329 9.152307 -0.003059 -0.001881 -0.010926 0.760412 0.890603 10.007245\n6330 9.158186 -0.003760 -0.001636 -0.011711 0.758348 0.866757 9.985516\n6331 9.164276 -0.003773 -0.001881 -0.011948 0.757413 0.878087 9.981415\n6332 9.170753 -0.003921 -0.002712 -0.011322 0.767422 0.902773 9.971433\n6333 9.176320 -0.004007 -0.002878 -0.010928 0.769103 0.897266 9.970108\n6334 9.182529 -0.004670 -0.002517 -0.010377 0.760304 0.878999 9.976494\n6335 9.189122 -0.004062 -0.002116 -0.010451 0.739377 0.890207 9.987419\n6336 9.194674 -0.003752 -0.002092 -0.010735 0.736423 0.887855 9.993621\n6337 9.201059 -0.003642 -0.002177 -0.011442 0.754303 0.868888 10.017076\n6338 9.206680 -0.003418 -0.002134 -0.011461 0.764497 0.873526 10.020012\n6339 9.213000 -0.003414 -0.002249 -0.010812 0.772347 0.905656 10.010726\n6340 9.218640 -0.003230 -0.002204 -0.010617 0.765581 0.908533 10.013017\n6341 9.225092 -0.003347 -0.002223 -0.010187 0.764815 0.884916 10.007833\n6342 9.230699 -0.003512 -0.002826 -0.010266 0.767994 0.890332 10.013416\n6343 9.237113 -0.003103 -0.002739 -0.010363 0.759614 0.911457 10.031140\n6344 9.242897 -0.003064 -0.002042 -0.010247 0.757768 0.900728 10.026352\n6345 9.249238 -0.003636 -0.001255 -0.010866 0.771304 0.875591 10.001030\n6346 9.254967 -0.003556 -0.001221 -0.010981 0.774475 0.880375 10.001883\n6347 9.261182 -0.003768 -0.001789 -0.011461 0.763749 0.879930 10.015193\n6348 9.266908 -0.003755 -0.002084 -0.011571 0.762794 0.871808 10.011559\n6349 9.273511 -0.003470 -0.002193 -0.010830 0.757391 0.875617 10.001682\n6350 9.279058 -0.003011 -0.002343 -0.010444 0.755971 0.893638 9.996119\n6351 9.285189 -0.003167 -0.002393 -0.010236 0.753964 0.895107 9.993303\n6352 9.291178 -0.003538 -0.002371 -0.010344 0.759062 0.880620 9.996619\n6353 9.297278 -0.003494 -0.002189 -0.010468 0.765717 0.884689 10.000309\n6354 9.303245 -0.003365 -0.002400 -0.010538 0.773280 0.897781 10.006922\n6355 9.309396 -0.003660 -0.002628 -0.010737 0.790157 0.886835 10.025529\n6356 9.315390 -0.003663 -0.002502 -0.010701 0.795179 0.868899 10.030709\n6357 9.321516 -0.003386 -0.002514 -0.010186 0.775908 0.880345 10.020353\n6358 9.327289 -0.003113 -0.002705 -0.010372 0.767715 0.901741 10.004088\n6359 9.333412 -0.002487 -0.001934 -0.010695 0.752550 0.894408 9.990436\n6360 9.339596 -0.002937 -0.001637 -0.010816 0.750843 0.883544 9.988788\n6361 9.345598 -0.003204 -0.001810 -0.010614 0.741725 0.896048 9.992153\n6362 9.351599 -0.002853 -0.002187 -0.010432 0.736233 0.896217 10.004096\n6363 9.357539 -0.003110 -0.002431 -0.010172 0.760110 0.876216 10.015852\n6364 9.363514 -0.003422 -0.002335 -0.010391 0.767340 0.880177 10.017037\n6365 9.369604 -0.003554 -0.002336 -0.010519 0.770528 0.907073 10.020297\n6366 9.375714 -0.003742 -0.002386 -0.010409 0.771695 0.911037 10.023067\n6367 9.381677 -0.003981 -0.001697 -0.011000 0.768081 0.879173 10.042813\n6368 9.387739 -0.004021 -0.001510 -0.011444 0.764225 0.869545 10.041411\n6369 9.393770 -0.003454 -0.001966 -0.011342 0.758306 0.884748 10.005563\n6370 9.399828 -0.003096 -0.001946 -0.010969 0.769386 0.891145 9.998149\n6371 9.405762 -0.003019 -0.001754 -0.009718 0.787259 0.877892 10.003034\n6372 9.411967 -0.003100 -0.001635 -0.009357 0.787067 0.889417 10.007390\n6373 9.418029 -0.002496 -0.002195 -0.009281 0.769349 0.917384 10.021998\n6374 9.423956 -0.002269 -0.002025 -0.009789 0.758232 0.905579 10.021581\n6375 9.429848 -0.003210 -0.001458 -0.010283 0.755012 0.867459 10.010920\n6376 9.435920 -0.003499 -0.001307 -0.010309 0.753818 0.869115 10.008726\n6377 9.442029 -0.003222 -0.001441 -0.011015 0.763821 0.871088 10.025240\n6378 9.448170 -0.003055 -0.001726 -0.010908 0.780704 0.863676 10.031801\n6379 9.454295 -0.003197 -0.002391 -0.010461 0.780028 0.873172 10.030581\n6380 9.460205 -0.003491 -0.002752 -0.010441 0.764999 0.894932 10.034630\n6381 9.466171 -0.003929 -0.003030 -0.010627 0.747829 0.905290 10.019329\n6382 9.472277 -0.004174 -0.002932 -0.010638 0.750342 0.888183 10.014345\n6383 9.478589 -0.004502 -0.002666 -0.010707 0.756489 0.873904 9.996827\n6384 9.484394 -0.004347 -0.002610 -0.010943 0.752790 0.880943 9.987204\n6385 9.490525 -0.003784 -0.002410 -0.011156 0.755149 0.878337 9.990917\n6386 9.496483 -0.003541 -0.002035 -0.010938 0.761990 0.869382 9.996420\n6387 9.502552 -0.003375 -0.001392 -0.010242 0.756213 0.889960 9.995360\n6388 9.508634 -0.003616 -0.001425 -0.010573 0.750361 0.905867 9.997193\n6389 9.514608 -0.003867 -0.001784 -0.011175 0.742257 0.908153 10.011428\n6390 9.520740 -0.003968 -0.001756 -0.011371 0.745790 0.900168 10.012915\n6391 9.526676 -0.004643 -0.001719 -0.010968 0.773481 0.904920 9.982935\n6392 9.532651 -0.005584 -0.001991 -0.010698 0.804968 0.901521 9.930514\n6393 9.538621 -0.008076 -0.004000 -0.011024 0.854162 0.897831 9.815333\n6394 9.544671 -0.009800 -0.005111 -0.011986 0.826948 0.898216 9.782176\n6395 9.550848 -0.010578 -0.003095 -0.017095 0.696110 0.922276 9.790726\n6396 9.556941 -0.009432 -0.000213 -0.020094 0.648517 0.924983 9.831181\n6397 9.562899 -0.007258 0.005927 -0.022561 0.644376 0.911375 9.861098\n6398 9.568929 -0.007542 0.007811 -0.020761 0.659934 0.903129 9.873737\n6399 9.574983 -0.011564 0.004539 -0.013154 0.680973 0.903418 9.895349\n6400 9.581619 -0.014541 -0.006896 -0.006203 0.648994 0.904801 9.911237\n6401 9.587360 -0.014553 -0.014038 -0.004679 0.617910 0.885712 9.925120\n6402 9.593229 -0.013314 -0.020279 -0.005009 0.592581 0.865712 9.938437\n6403 9.599376 -0.007303 -0.028586 -0.009379 0.566336 0.856679 9.968206\n6404 9.605168 -0.004344 -0.029266 -0.011835 0.578857 0.845469 9.988737\n6405 9.611491 -0.002322 -0.024695 -0.017058 0.643800 0.809320 10.060836\n6406 9.617855 -0.002685 -0.020339 -0.019364 0.679676 0.808964 10.136662\n6407 9.623465 -0.002100 -0.010098 -0.021764 0.779673 0.824223 10.348164\n6408 9.629956 0.001671 -0.003212 -0.017832 0.940889 0.849419 10.548789\n6409 9.635516 0.001922 -0.002987 -0.012473 1.030556 0.896842 10.557388\n6410 9.641836 0.002353 -0.012355 0.001996 1.213966 1.056217 10.457858\n6411 9.647583 0.001173 -0.020471 0.008186 1.288603 1.092288 10.377930\n6412 9.654079 0.002031 -0.033525 0.011883 1.291906 0.992848 10.238248\n6413 9.659716 0.003848 -0.034372 0.008207 1.246675 0.923796 10.210270\n6414 9.665939 0.012998 -0.016902 -0.004738 1.146622 0.847159 10.144179\n6415 9.671652 0.018648 0.000335 -0.010197 1.094034 0.818029 10.130111\n6416 9.678101 0.023343 0.041747 -0.014482 0.924506 0.777277 10.069672\n6417 9.684025 0.023113 0.062615 -0.014575 0.790622 0.771922 10.036892\n6418 9.690018 0.018757 0.093571 -0.014423 0.484642 0.784883 10.017670\n6419 9.695800 0.016527 0.101043 -0.014533 0.357515 0.786122 10.013453\n6420 9.702053 0.014546 0.096911 -0.012800 0.176218 0.800438 9.994072\n6421 9.707978 0.013971 0.084733 -0.009661 0.132601 0.816200 9.957596\n6422 9.714029 0.009339 0.043387 -0.000212 0.114237 0.838942 9.869218\n6423 9.720109 0.004990 0.017317 0.004155 0.135759 0.847730 9.848804\n6424 9.726119 -0.007303 -0.038227 0.006088 0.286243 0.907259 9.819737\n6425 9.732246 -0.012248 -0.064705 0.002820 0.398388 0.972897 9.818948\n6426 9.738179 -0.015581 -0.106570 -0.008876 0.691602 1.068769 9.857382\n6427 9.744204 -0.015276 -0.119952 -0.014741 0.851169 1.066943 9.859622\n6428 9.750135 -0.012703 -0.126992 -0.020823 1.111173 1.022686 9.795775\n6429 9.756255 -0.012216 -0.120219 -0.020960 1.195958 1.003092 9.740733\n6430 9.762321 -0.014207 -0.088372 -0.017483 1.317428 0.963101 9.629641\n6431 9.768313 -0.015012 -0.064524 -0.015929 1.336014 0.948531 9.616862\n6432 9.774523 -0.014135 -0.006859 -0.015768 1.262615 0.930772 9.666356\n6433 9.780475 -0.010718 0.023836 -0.017033 1.179391 0.919278 9.742953\n6434 9.786791 -0.003318 0.081955 -0.018502 0.986727 0.871119 9.894807\n6435 9.792558 -0.000946 0.105236 -0.017378 0.888218 0.842950 9.952809\n6436 9.798608 -0.003313 0.130979 -0.012141 0.660727 0.812648 10.036556\n6437 9.804488 -0.006940 0.131973 -0.010052 0.543407 0.804911 10.068700\n6438 9.810630 -0.014510 0.109407 -0.010913 0.327524 0.773743 10.119226\n6439 9.816620 -0.016242 0.087417 -0.013730 0.250508 0.782239 10.139095\n6440 9.822638 -0.014444 0.030257 -0.017919 0.189417 0.883090 10.126253\n6441 9.828705 -0.012499 -0.001699 -0.017501 0.224885 0.933430 10.101780\n6442 9.834778 -0.014411 -0.062886 -0.014300 0.409982 0.984984 10.017718\n6443 9.840819 -0.019470 -0.093194 -0.012191 0.590875 0.993969 9.964357\n6444 9.846860 -0.027249 -0.121642 -0.010782 0.930489 0.980117 9.897726\n6445 9.853140 -0.028219 -0.124375 -0.011223 1.095676 0.957551 9.876629\n6446 9.859015 -0.021010 -0.104214 -0.011252 1.323943 0.928079 9.889575\n6447 9.864977 -0.015642 -0.081643 -0.009978 1.365612 0.932405 9.913068\n6448 9.870963 -0.005937 -0.016325 -0.006864 1.329471 0.927121 10.004899\n6449 9.877148 -0.003993 0.021864 -0.005347 1.273903 0.902366 10.057256\n6450 9.883105 -0.007318 0.092334 -0.002531 1.152283 0.851520 10.141497\n6451 9.889355 -0.010491 0.118443 -0.001225 1.082818 0.841377 10.194343\n6452 9.895213 -0.015543 0.142837 0.004170 0.941798 0.801418 10.314758\n6453 9.901214 -0.017433 0.140379 0.010977 0.884074 0.770126 10.318938\n6454 9.907320 -0.022622 0.110412 0.033217 0.715979 0.760329 10.232160\n6455 9.913293 -0.028679 0.087056 0.046971 0.584186 0.786776 10.152375\n6456 9.919596 -0.049882 0.036864 0.071975 0.315350 0.868699 9.977109\n6457 9.925441 -0.063705 0.013940 0.080911 0.227057 0.918644 9.882580\n6458 9.931491 -0.089713 -0.022954 0.091137 0.147583 0.983931 9.753752\n6459 9.937501 -0.101150 -0.036781 0.093085 0.171386 0.997627 9.730695\n6460 9.943515 -0.115423 -0.055795 0.092639 0.314116 1.011946 9.699657\n6461 9.949438 -0.117320 -0.060577 0.090551 0.431181 0.992830 9.705817\n6462 9.955456 -0.116449 -0.062005 0.080505 0.665286 0.924924 9.768022\n6463 9.961542 -0.114603 -0.059109 0.072113 0.757435 0.872332 9.796737\n6464 9.967631 -0.105528 -0.049869 0.044825 0.886845 0.766822 9.907175\n6465 9.973803 -0.097297 -0.044651 0.028207 0.893213 0.720649 9.973320\n6466 9.979732 -0.073149 -0.032056 -0.003737 0.869352 0.709420 10.111029\n6467 9.985798 -0.057816 -0.025370 -0.017420 0.871669 0.720593 10.180590\n6468 9.992102 -0.029069 -0.012996 -0.035915 0.925825 0.728242 10.295136\n6469 9.997914 -0.017466 -0.007309 -0.040437 0.968664 0.721611 10.333450\n6470 10.004021 -0.002372 0.003394 -0.040534 0.949051 0.695034 10.457437\n6471 10.010630 0.002678 0.013711 -0.032300 0.870946 0.696998 10.552228\n6472 10.016091 0.006366 0.019159 -0.024983 0.811815 0.723401 10.595881\n6473 10.022590 0.008144 0.024556 -0.015678 0.751498 0.760185 10.605212\n6474 10.028282 0.011957 0.032970 0.003763 0.676519 0.824706 10.459332\n6475 10.034693 0.010677 0.030644 0.017274 0.681741 0.830648 10.183016\n6476 10.040353 0.009015 0.022805 0.018957 0.722088 0.828084 10.007124\n6477 10.046812 0.005918 -0.002838 0.009590 0.787306 0.848114 9.703754\n6478 10.052587 0.005045 -0.017471 -0.000192 0.800814 0.873697 9.587344\n6479 10.058950 0.005358 -0.040753 -0.023998 0.845492 0.890316 9.346943\n6480 10.064467 0.004127 -0.047501 -0.035393 0.870455 0.894403 9.233372\n6481 10.070866 -0.007770 -0.047608 -0.051371 0.884965 0.934436 9.039076\n6482 10.076563 -0.018307 -0.040602 -0.056102 0.850869 0.971869 8.998714\n6483 10.082968 -0.042231 -0.018078 -0.061209 0.703754 1.023902 8.975445\n6484 10.088590 -0.055656 -0.005881 -0.062061 0.630203 1.012819 8.973216\n6485 10.095289 -0.085043 0.013059 -0.060133 0.527513 1.006601 8.901564\n6486 10.100706 -0.097331 0.018196 -0.056612 0.527482 1.007630 8.916309\n6487 10.106921 -0.120647 0.020348 -0.045577 0.674498 0.902457 9.257083\n6488 10.112688 -0.133807 0.020255 -0.039661 0.785436 0.835519 9.508221\n6489 10.119182 -0.157234 0.018694 -0.033848 1.006946 0.806143 10.159093\n6490 10.124849 -0.164723 0.012399 -0.033997 1.081446 0.791059 10.523538\n6491 10.130922 -0.177711 -0.008726 -0.041764 1.117589 0.611273 10.969481\n6492 10.136793 -0.177600 -0.022851 -0.047759 1.023887 0.617600 11.162325\n6493 10.143067 -0.190032 -0.036011 -0.053229 0.831563 1.089457 11.234245\n6494 10.149021 -0.194278 -0.029305 -0.052261 0.747528 0.963330 11.266843\n6495 10.155081 -0.205021 0.006355 -0.040717 0.778890 0.401374 11.116695\n6496 10.161018 -0.203520 0.028448 -0.032395 0.897490 0.241115 11.065840\n6497 10.167075 -0.198548 0.077100 -0.011897 1.057407 0.228749 11.011038\n6498 10.173068 -0.185320 0.101935 0.001099 1.083114 0.255340 11.060328\n6499 10.179327 -0.140579 0.133309 0.024219 1.133392 0.333642 11.300482\n6500 10.185287 -0.110238 0.135245 0.029311 1.125397 0.443797 11.278152\n6501 10.191358 -0.045407 0.119287 0.017855 0.968296 0.516456 11.015478\n6502 10.197502 -0.010449 0.105170 -0.001012 0.898789 0.440643 10.893853\n6503 10.203494 0.068580 0.074096 -0.060231 0.609523 0.307598 10.597919\n6504 10.209266 0.114389 0.061392 -0.095737 0.449906 0.351989 10.466322\n6505 10.215420 0.211369 0.049317 -0.183496 0.250756 0.518706 10.458218\n6506 10.221432 0.248358 0.054176 -0.224008 0.177963 0.539491 10.478325\n6507 10.227437 0.299381 0.083456 -0.304933 0.116342 0.478858 10.458469\n6508 10.233515 0.308696 0.103818 -0.342302 0.185088 0.466355 10.325356\n6509 10.239474 0.313320 0.142661 -0.385755 0.490460 0.660224 10.074298\n6510 10.245671 0.317610 0.155370 -0.385001 0.540105 0.848244 10.151958\n6511 10.251802 0.342892 0.163728 -0.349627 0.285915 1.087303 10.504568\n6512 10.257663 0.362880 0.163273 -0.322156 0.157351 1.105714 10.568433\n6513 10.263679 0.387772 0.164079 -0.260714 0.175832 1.072993 10.339029\n6514 10.269776 0.386180 0.168692 -0.227602 0.269387 1.063426 10.112363\n6515 10.275773 0.371705 0.189997 -0.147487 0.345125 1.156768 10.009554\n6516 10.281803 0.365680 0.198428 -0.103240 0.378528 1.154063 10.140329\n6517 10.287794 0.359972 0.196609 -0.026934 0.631259 0.922024 10.385328\n6518 10.293892 0.360702 0.182199 0.002529 0.796891 0.796790 10.583606\n6519 10.300187 0.351825 0.134310 0.043495 1.055196 0.553636 10.965621\n6520 10.305946 0.339383 0.109767 0.052875 1.145234 0.492233 11.191676\n6521 10.312030 0.291817 0.066944 0.059032 1.381163 0.565848 11.359482\n6522 10.318204 0.261293 0.051602 0.058383 1.512667 0.605011 11.251451\n6523 10.324326 0.200635 0.034481 0.041545 1.542797 0.563956 10.971468\n6524 10.330223 0.175562 0.029691 0.022713 1.387319 0.583415 10.830598\n6525 10.336207 0.137406 0.030507 -0.033042 0.875931 0.647515 10.548422\n6526 10.342244 0.121410 0.035267 -0.066618 0.675266 0.688497 10.501270\n6527 10.348364 0.086958 0.046183 -0.130802 0.488690 0.789749 10.660783\n6528 10.354329 0.074977 0.051330 -0.156188 0.453765 0.810098 10.799552\n6529 10.360276 0.072869 0.056981 -0.196097 0.526771 0.699058 11.093638\n6530 10.366493 0.084192 0.056957 -0.212661 0.581516 0.568747 11.184180\n6531 10.372434 0.131666 0.056108 -0.240497 0.693687 0.413030 11.244685\n6532 10.378544 0.164552 0.055111 -0.251772 0.704139 0.417059 11.252433\n6533 10.384576 0.232818 0.053995 -0.265788 0.633900 0.608810 11.162602\n6534 10.390688 0.268217 0.055585 -0.268708 0.578305 0.715855 11.104303\n6535 10.396581 0.329393 0.062316 -0.271145 0.509149 0.828075 10.999994\n6536 10.402854 0.349590 0.066589 -0.274753 0.520082 0.842017 10.958426\n6537 10.408646 0.375589 0.072258 -0.289091 0.518968 0.754594 10.894670\n6538 10.414757 0.381952 0.071571 -0.298145 0.526417 0.703261 10.867646\n6539 10.420817 0.370814 0.062273 -0.310455 0.503303 0.853789 10.984600\n6540 10.426821 0.353689 0.054010 -0.310798 0.438647 0.978957 11.084476\n6541 10.432902 0.320604 0.033798 -0.299026 0.252828 1.140378 11.213117\n6542 10.438924 0.304581 0.019390 -0.287242 0.182294 1.190518 11.232239\n6543 10.445087 0.275992 -0.020342 -0.249573 0.165837 1.366759 11.114620\n6544 10.451681 0.248757 -0.063065 -0.193973 0.225168 1.630076 11.025450\n6545 10.457093 0.234252 -0.082839 -0.160690 0.240084 1.700990 10.962797\n6546 10.463057 0.217597 -0.099724 -0.125474 0.243465 1.713995 10.868952\n6547 10.469168 0.176440 -0.121170 -0.056480 0.266214 1.611282 10.693416\n6548 10.475699 0.150123 -0.126615 -0.025041 0.280462 1.515644 10.608174\n6549 10.481188 0.092485 -0.124789 0.031917 0.302954 1.327026 10.429530\n6550 10.487639 0.035322 -0.107576 0.076876 0.383891 1.233160 10.421170\n6551 10.493317 0.009160 -0.093271 0.094995 0.447609 1.212257 10.441195\n6552 10.499789 -0.041015 -0.049386 0.126468 0.602484 1.020450 10.474110\n6553 10.505571 -0.060730 -0.026473 0.133731 0.684011 0.875605 10.412258\n6554 10.511770 -0.096230 0.019316 0.139044 0.708053 0.716821 10.344062\n6555 10.517655 -0.110874 0.039928 0.138885 0.620686 0.781519 10.328511\n6556 10.523918 -0.126460 0.072645 0.134731 0.277850 0.894490 10.446863\n6557 10.529635 -0.128817 0.082183 0.131563 0.127232 0.890409 10.545280\n6558 10.536019 -0.129444 0.088804 0.125527 0.077558 0.790743 10.674313\n6559 10.541849 -0.130606 0.087174 0.124460 0.179899 0.705220 10.724609\n6560 10.548266 -0.135044 0.075971 0.131264 0.511669 0.526505 10.769274\n6561 10.553885 -0.136183 0.069437 0.139142 0.677841 0.448701 10.799962\n6562 10.559998 -0.134409 0.056015 0.160197 0.862829 0.387347 10.940505\n6563 10.565853 -0.133910 0.048137 0.169265 0.878543 0.381751 11.013773\n6564 10.572057 -0.136189 0.028647 0.173150 0.711632 0.363165 11.127440\n6565 10.577856 -0.139240 0.016981 0.165229 0.571579 0.395110 11.183762\n6566 10.584226 -0.149684 -0.007877 0.131724 0.375164 0.585285 11.305752\n6567 10.589986 -0.152785 -0.019198 0.111051 0.339632 0.670829 11.346496\n6568 10.596102 -0.147590 -0.039608 0.076329 0.451042 0.715084 11.330078\n6569 10.602039 -0.138332 -0.049436 0.065483 0.538746 0.709682 11.258674\n6570 10.608523 -0.092340 -0.081555 0.063554 0.649476 0.794601 11.326586\n6571 10.614132 -0.058355 -0.108962 0.071989 0.714518 0.807956 11.415315\n6572 10.620223 0.013199 -0.187634 0.099322 0.836470 0.687971 11.471449\n6573 10.626267 0.045395 -0.237877 0.116078 0.818471 0.673855 11.453917\n6574 10.632352 0.086749 -0.341637 0.146277 0.604591 0.702454 11.345156\n6575 10.638349 0.094819 -0.388785 0.154871 0.456964 0.669372 11.307323\n6576 10.644292 0.087002 -0.469143 0.154734 0.353192 0.481212 11.138394\n6577 10.650588 0.072563 -0.498286 0.145801 0.399129 0.388346 10.956837\n6578 10.656248 0.024743 -0.531190 0.113908 0.496434 0.238102 10.538388\n6579 10.662422 -0.004381 -0.537372 0.096108 0.527693 0.181239 10.310570\n6580 10.668408 -0.063681 -0.528047 0.068845 0.660194 0.073404 9.916454\n6581 10.674605 -0.094182 -0.513277 0.060827 0.769853 0.090390 9.859980\n6582 10.680587 -0.155389 -0.467872 0.053200 0.942250 0.296093 9.889629\n6583 10.686663 -0.180519 -0.438618 0.050774 0.941269 0.428838 9.979731\n6584 10.692477 -0.282005 -0.387148 0.026396 0.425028 1.053086 10.932079\n6585 10.698637 -0.317024 -0.367704 0.014783 0.483141 1.244361 10.858889\n6586 10.704570 -0.351871 -0.342400 -0.000197 0.830236 0.964539 10.703673\n6587 10.710895 -0.380956 -0.351196 0.003779 1.053711 0.811631 10.510999\n6588 10.716992 -0.411736 -0.382733 0.032777 1.016326 0.527018 9.549190\n6589 10.722765 -0.394803 -0.395197 0.054396 0.947506 0.547096 9.356106\n6590 10.728887 -0.354711 -0.426768 0.087777 0.761203 0.562924 9.335575\n6591 10.734962 -0.326454 -0.432397 0.095928 0.635776 0.584022 9.221026\n6592 10.741140 -0.253227 -0.418180 0.103104 0.632052 0.639837 9.498271\n6593 10.746976 -0.228925 -0.403636 0.102697 0.734384 0.587572 9.605746\n6594 10.753134 -0.189682 -0.343551 0.099248 0.885954 0.452533 9.641794\n6595 10.759142 -0.166866 -0.305228 0.096015 0.999670 0.340739 9.732946\n6596 10.765101 -0.139784 -0.231912 0.075463 1.167885 0.142549 9.680863\n6597 10.771245 -0.119148 -0.194959 0.061207 1.221872 0.124492 9.511936\n6598 10.777267 -0.071278 -0.132543 0.038374 1.276116 0.272178 9.219400\n6599 10.783470 -0.047147 -0.107585 0.028379 1.167203 0.334973 8.973708\n6600 10.789391 0.011273 -0.064623 0.006235 0.847801 0.537646 8.865024\n6601 10.795416 0.052134 -0.057046 -0.006734 0.774927 0.677405 9.248304\n6602 10.801371 0.135539 -0.070081 -0.037841 0.860193 0.962918 9.920847\n6603 10.807446 0.175151 -0.086243 -0.055921 0.924366 1.004163 10.077535\n6604 10.813759 0.234713 -0.143606 -0.093666 0.961762 0.882256 10.027168\n6605 10.819604 0.253364 -0.175308 -0.114186 0.893025 0.840594 9.908791\n6606 10.825640 0.292248 -0.238917 -0.154709 0.658054 0.865392 9.883633\n6607 10.831636 0.308124 -0.276448 -0.172168 0.583346 0.839269 9.831629\n6608 10.837730 0.317416 -0.355915 -0.206352 0.447272 0.763465 9.594402\n6609 10.843758 0.313799 -0.393069 -0.224950 0.356742 0.785314 9.449750\n6610 10.849862 0.289059 -0.449336 -0.259460 0.093387 1.153224 9.623171\n6611 10.855729 0.276630 -0.459234 -0.277395 -0.044108 1.672302 9.972631\n6612 10.861889 0.243925 -0.422972 -0.305209 -0.026703 1.855451 10.143852\n6613 10.867863 0.229945 -0.386471 -0.313051 0.209778 1.625192 9.825741\n6614 10.873883 0.214349 -0.301887 -0.315892 0.579088 1.198329 9.184292\n6615 10.879970 0.212964 -0.248497 -0.313154 0.570756 1.252375 9.065441\n6616 10.885941 0.228193 -0.127906 -0.303963 0.511938 1.426097 8.839250\n6617 10.892418 0.238411 -0.067766 -0.302295 0.533477 1.439806 8.578327\n6618 10.897973 0.231907 0.046746 -0.321859 0.297085 1.597100 8.413287\n6619 10.904513 0.151792 0.159369 -0.377520 -0.406383 1.727234 8.516318\n6620 10.910153 0.089454 0.217115 -0.415899 -0.586093 1.642760 8.518538\n6621 10.916968 -0.071421 0.316501 -0.500887 -0.219167 1.013543 8.642498\n6622 10.923223 -0.168906 0.357177 -0.539742 0.166639 0.584166 8.656918\n6623 10.929232 -0.382624 0.417620 -0.631421 0.608432 1.080394 8.702863\n6624 10.935260 -0.447663 0.431031 -0.662452 0.511546 1.264587 8.836898\n6625 10.941398 -0.605722 0.466881 -0.749377 0.270609 1.154808 9.368918\n6626 10.947385 -0.682892 0.484297 -0.799468 0.198850 1.148474 9.516165\n6627 10.953345 -0.863351 0.515350 -0.894448 0.274533 0.646571 9.373500\n6628 10.959498 -0.927625 0.522246 -0.912702 0.648459 0.179851 9.571332\n6629 10.965565 -1.011834 0.521757 -0.872676 1.312220 0.230662 10.176263\n6630 10.971422 -1.024419 0.511055 -0.815686 1.435199 0.566391 10.373011\n6631 10.977692 -1.008880 0.448474 -0.657514 1.528343 0.803152 10.586741\n6632 10.983635 -0.992924 0.396571 -0.569660 1.481440 0.685624 10.557731\n6633 10.989629 -0.959234 0.265249 -0.384191 1.248992 0.706049 10.305775\n6634 10.995644 -0.943329 0.190572 -0.287046 1.117961 0.824012 10.161353\n6635 11.001752 -0.889845 0.047492 -0.092478 0.805453 0.831824 9.929035\n6636 11.007752 -0.847227 -0.009713 -0.000461 0.631301 0.690327 9.828696\n6637 11.013755 -0.749169 -0.085046 0.148657 0.484794 0.265758 9.455339\n6638 11.019756 -0.701576 -0.102177 0.196796 0.559207 0.067345 9.152694\n6639 11.025861 -0.625212 -0.092634 0.240093 0.598605 -0.250947 8.680708\n6640 11.032097 -0.597278 -0.065816 0.241435 0.497327 -0.354507 8.604286\n6641 11.038161 -0.542985 0.034926 0.214077 0.110595 -0.370858 8.724270\n6642 11.044013 -0.502764 0.106256 0.189286 -0.080600 -0.361709 8.823758\n6643 11.050043 -0.390116 0.276437 0.123967 -0.188423 -0.562591 8.990414\n6644 11.056090 -0.327928 0.366587 0.083426 -0.155780 -0.776760 9.159109\n6645 11.062261 -0.186687 0.548429 -0.001702 -0.127091 -1.201452 9.404926\n6646 11.068106 -0.110545 0.638341 -0.043015 -0.078454 -1.440107 9.595690\n6647 11.074357 0.041199 0.808291 -0.119149 0.224028 -1.462870 9.760204\n6648 11.080296 0.112540 0.884171 -0.151900 0.293654 -1.277190 9.755708\n6649 11.086296 0.263799 1.016694 -0.205951 0.125457 -0.797625 9.597677\n6650 11.092853 0.415182 1.109856 -0.266061 -0.215344 -0.451049 9.157959\n6651 11.098519 0.480277 1.137836 -0.296637 -0.383517 -0.285371 8.909727\n6652 11.105014 0.595869 1.149400 -0.347193 -0.170668 0.163842 8.763815\n6653 11.110633 0.640452 1.136166 -0.364096 0.106194 0.651217 8.972642\n6654 11.117119 0.719554 1.080023 -0.368595 0.482094 1.643131 9.539361\n6655 11.122731 0.752129 1.041418 -0.358916 0.544169 1.831725 9.857045\n6656 11.128999 0.784897 0.944468 -0.324573 0.281066 1.791906 10.448021\n6657 11.134610 0.788439 0.887005 -0.296534 0.004347 1.732009 10.590817\n6658 11.141178 0.775468 0.752555 -0.208051 -0.448827 1.719682 10.733760\n6659 11.146761 0.760756 0.672476 -0.148493 -0.558139 1.727335 10.725948\n6660 11.153100 0.718477 0.489034 -0.007469 -0.397109 1.754562 10.752929\n6661 11.158680 0.690840 0.388246 0.067783 -0.114416 1.700370 10.964249\n6662 11.165167 0.615172 0.183514 0.210057 0.584852 1.527021 11.347870\n6663 11.171096 0.566268 0.086030 0.274215 0.783290 1.463515 11.377454\n6664 11.177182 0.438978 -0.095912 0.397104 0.520144 1.148486 11.021063\n6665 11.182994 0.371651 -0.177692 0.457436 0.076000 0.933491 10.792485\n6666 11.189236 0.276677 -0.320991 0.559900 -0.782103 1.179831 10.395339\n6667 11.195100 0.253668 -0.385041 0.597828 -0.927907 1.578369 10.281379\n6668 11.201187 0.262345 -0.512535 0.642935 -0.620885 2.173064 10.087302\n6669 11.207009 0.287476 -0.575540 0.646195 -0.325437 2.276958 10.060072\n6670 11.213107 0.359353 -0.697619 0.615947 0.193998 2.403268 10.026214\n6671 11.219105 0.396593 -0.752147 0.592474 0.524086 2.419812 10.065118\n6672 11.225176 0.466943 -0.839740 0.549341 1.410282 2.211646 10.387894\n6673 11.231301 0.504388 -0.870449 0.531580 1.786163 2.038559 10.609995\n6674 11.237519 0.575434 -0.899580 0.503385 2.186816 1.737127 10.962522\n6675 11.243616 0.596543 -0.895817 0.490017 2.249276 1.582663 10.962125\n6676 11.249545 0.584668 -0.840472 0.458982 2.116635 1.337449 10.607659\n6677 11.255556 0.552706 -0.786400 0.440443 1.894831 1.280640 10.283763\n6678 11.261555 0.450220 -0.634293 0.392791 1.243386 1.204698 9.749336\n6679 11.267546 0.390347 -0.544493 0.360126 0.880473 1.141745 9.662349\n6680 11.273677 0.279866 -0.351874 0.273379 0.264382 0.974583 9.805758\n6681 11.279770 0.231113 -0.254635 0.218303 0.171315 0.882218 9.946472\n6682 11.285679 0.129480 -0.073929 0.086344 0.472859 0.907633 10.162771\n6683 11.291680 0.072382 0.005781 0.013550 0.809827 1.021144 10.270680\n6684 11.297814 -0.049789 0.137366 -0.130811 1.554935 1.209231 10.477469\n6685 11.304176 -0.108044 0.187440 -0.196795 1.837313 1.269439 10.483756\n6686 11.309724 -0.196116 0.251275 -0.308625 2.162315 1.477156 10.274316\n6687 11.315795 -0.221748 0.265573 -0.353906 2.232638 1.644225 10.100118\n6688 11.321978 -0.234750 0.266956 -0.423207 2.288731 2.031322 9.752307\n6689 11.328231 -0.229896 0.257898 -0.447866 2.326884 2.161514 9.655076\n6690 11.334603 -0.211035 0.228250 -0.486486 2.571639 2.163521 9.780776\n6691 11.340353 -0.195584 0.210476 -0.503694 2.756864 2.099571 9.950394\n6692 11.346038 -0.140196 0.176323 -0.536202 2.978372 2.028559 10.284345\n6693 11.352182 -0.101478 0.161649 -0.553070 2.895736 2.043804 10.401639\n6694 11.358116 0.000262 0.141671 -0.592514 2.321522 2.134005 10.385744\n6695 11.364237 0.058786 0.137437 -0.615606 1.893783 2.211585 10.257969\n6696 11.370358 0.168505 0.135730 -0.664612 1.025539 2.402447 9.830518\n6697 11.376195 0.213880 0.135443 -0.688915 0.683006 2.545272 9.660979\n6698 11.382301 0.286365 0.130387 -0.728474 0.308076 2.871790 9.594418\n6699 11.388271 0.313113 0.122871 -0.742403 0.358170 2.933063 9.664965\n6700 11.394580 0.345350 0.090890 -0.756721 0.923206 2.750190 9.788925\n6701 11.400512 0.349389 0.065209 -0.755738 1.336626 2.629456 9.831249\n6702 11.406507 0.333369 0.000291 -0.736812 2.045787 2.631616 9.891877\n6703 11.412589 0.310004 -0.043599 -0.717999 2.259461 2.785760 9.910866\n6704 11.418573 0.260375 -0.108081 -0.691489 2.201037 3.000459 9.855406\n6705 11.424588 0.234919 -0.134370 -0.685513 2.026114 3.034821 9.751936\n6706 11.430626 0.202784 -0.172997 -0.693011 1.634444 2.950790 9.391315\n6707 11.436763 0.194993 -0.183418 -0.703751 1.400171 2.869059 9.284524\n6708 11.442610 0.197105 -0.181443 -0.727413 0.899846 2.687208 9.186927\n6709 11.448802 0.203558 -0.167008 -0.736749 0.683717 2.615372 9.190119\n6710 11.455012 0.213144 -0.120030 -0.745707 0.422816 2.515721 9.106758\n6711 11.460839 0.214085 -0.090883 -0.745719 0.389074 2.483102 9.007608\n6712 11.466761 0.210434 -0.031155 -0.739303 0.356398 2.451019 8.829643\n6713 11.473014 0.209163 -0.003667 -0.733174 0.291662 2.448563 8.728037\n6714 11.478823 0.210197 0.041577 -0.710505 0.113270 2.558565 8.480700\n6715 11.485010 0.213649 0.059278 -0.691965 0.026425 2.676742 8.398062\n6716 11.491065 0.214703 0.086266 -0.637502 -0.085520 2.904287 8.397174\n6717 11.497184 0.210503 0.096988 -0.603959 -0.069887 2.955781 8.460927\n6718 11.503428 0.193728 0.110830 -0.532868 0.155662 2.971508 8.663203\n6719 11.509685 0.181369 0.112760 -0.495966 0.342548 2.990715 8.742654\n6720 11.515216 0.156104 0.106673 -0.417637 0.669733 3.078889 8.782727\n6721 11.521625 0.143418 0.098781 -0.374239 0.735424 3.129567 8.756522\n6722 11.527331 0.116075 0.072314 -0.276659 0.646469 3.171639 8.575246\n6723 11.533824 0.078821 0.036238 -0.176708 0.334911 3.138672 8.521983\n6724 11.539387 0.058888 0.014901 -0.132153 0.140566 3.151497 8.482990\n6725 11.545895 0.023366 -0.029529 -0.061521 -0.229663 3.305574 8.452031\n6726 11.551489 0.011022 -0.053080 -0.035944 -0.386903 3.400672 8.469485\n6727 11.557930 0.002984 -0.098228 -0.000201 -0.500129 3.433240 8.567276\n6728 11.563584 0.011009 -0.118110 0.011874 -0.419139 3.345596 8.660852\n6729 11.570020 0.043271 -0.153984 0.030652 -0.048359 2.980575 8.857680\n6730 11.575682 0.063718 -0.169370 0.038956 0.206307 2.722704 8.952810\n6731 11.581948 0.105730 -0.192510 0.055447 0.672413 2.191767 9.105476\n6732 11.587707 0.125591 -0.199657 0.064485 0.838795 1.950838 9.138505\n6733 11.593858 0.162097 -0.201967 0.081289 0.903493 1.570071 9.139265\n6734 11.599774 0.178204 -0.196763 0.086325 0.749595 1.490375 9.132388\n6735 11.606281 0.202805 -0.168184 0.080599 0.173606 1.621015 9.095504\n6736 11.611973 0.211061 -0.145507 0.066747 -0.156163 1.763354 9.039315\n6737 11.618130 0.216046 -0.088224 0.014104 -0.647101 2.006817 8.850069\n6738 11.623966 0.212629 -0.057281 -0.023764 -0.757683 2.075878 8.775117\n6739 11.629894 0.198899 0.001542 -0.114939 -0.720636 2.097029 8.734112\n6740 11.636130 0.191780 0.026723 -0.163590 -0.598535 2.051554 8.764016\n6741 11.642213 0.173963 0.064588 -0.255654 -0.230089 1.875825 8.875591\n6742 11.648321 0.160182 0.076030 -0.296258 -0.040238 1.808527 8.942480\n6743 11.654175 0.121322 0.085312 -0.361706 0.211868 1.794914 9.065740\n6744 11.660251 0.093811 0.083764 -0.387457 0.230832 1.830163 9.139346\n6745 11.666616 0.030079 0.070945 -0.427002 0.082902 1.888703 9.210538\n6746 11.672178 -0.003185 0.060129 -0.440768 -0.044147 1.879085 9.201000\n6747 11.678356 -0.065401 0.028489 -0.453453 -0.326574 1.865349 9.199170\n6748 11.684275 -0.091380 0.008677 -0.451062 -0.495645 1.901957 9.233187\n6749 11.690269 -0.127028 -0.037888 -0.425895 -0.887257 1.950199 9.352443\n6750 11.696547 -0.138273 -0.064838 -0.403469 -1.062942 1.902415 9.465064\n6751 11.702799 -0.150390 -0.127643 -0.343785 -1.229079 1.684794 9.782664\n6752 11.708466 -0.148032 -0.161407 -0.307501 -1.189831 1.598013 9.980004\n6753 11.714592 -0.126026 -0.230712 -0.220389 -0.917581 1.532268 10.334202\n6754 11.720658 -0.107431 -0.266014 -0.169945 -0.738229 1.557595 10.453644\n6755 11.726679 -0.059439 -0.337102 -0.059551 -0.338872 1.680126 10.518344\n6756 11.732600 -0.031167 -0.372558 -0.004407 -0.132931 1.737131 10.506057\n6757 11.738632 0.023048 -0.442678 0.092870 0.235703 1.821260 10.404492\n6758 11.744782 0.043864 -0.476035 0.130232 0.354328 1.859190 10.274832\n6759 11.750769 0.070731 -0.536565 0.175652 0.499593 1.884572 9.871350\n6760 11.756933 0.076964 -0.563297 0.183940 0.558578 1.871913 9.664683\n6761 11.762899 0.081468 -0.603523 0.177862 0.708943 1.770121 9.378891\n6762 11.769195 0.082546 -0.614931 0.166496 0.830543 1.691628 9.312738\n6763 11.774909 0.086206 -0.618106 0.135015 1.019174 1.471517 9.274212\n6764 11.781063 0.089301 -0.608962 0.117273 1.042415 1.361514 9.258908\n6765 11.787113 0.098419 -0.573237 0.082725 0.916865 1.273658 9.277319\n6766 11.792907 0.104566 -0.548640 0.069017 0.791420 1.269767 9.319514\n6767 11.799030 0.124140 -0.489002 0.051532 0.543949 1.278961 9.533026\n6768 11.805147 0.139884 -0.454414 0.046279 0.458542 1.253950 9.659365\n6769 11.811218 0.180394 -0.375610 0.039438 0.364587 1.204131 9.876289\n6770 11.817311 0.202121 -0.332445 0.036850 0.368321 1.205446 9.917451\n6771 11.823324 0.238883 -0.240769 0.031631 0.422359 1.227260 9.911855\n6772 11.829341 0.257697 -0.181076 0.029329 0.476318 1.210962 9.870890\n6773 11.835553 0.285829 -0.098896 0.028515 0.598631 1.115440 9.762338\n6774 11.841455 0.304809 -0.054940 0.030255 0.674395 1.047638 9.719829\n6775 11.847567 0.350512 0.029177 0.047988 0.852216 1.187746 9.743111\n6776 11.853392 0.368050 0.052178 0.058379 0.914329 1.333148 9.753188\n6777 11.859538 0.414417 0.100454 0.090193 1.104692 1.621353 9.766814\n6778 11.865509 0.430369 0.114968 0.104472 1.250006 1.622412 9.805888\n6779 11.871678 0.436134 0.126703 0.118885 1.585550 1.528255 10.019833\n6780 11.877907 0.433580 0.128536 0.118671 1.739045 1.566249 10.125282\n6781 11.883615 0.426766 0.131182 0.111127 1.861156 1.711225 10.203232\n6782 11.889643 0.420913 0.132400 0.106292 1.831113 1.771595 10.115444\n6783 11.895597 0.404499 0.137579 0.094513 1.646700 1.916996 9.921336\n6784 11.901718 0.394857 0.143592 0.087582 1.480370 2.030553 9.876670\n6785 11.907753 0.377829 0.164110 0.072152 1.059038 2.188957 9.811982\n6786 11.913875 0.366821 0.180729 0.064982 0.782932 2.175863 9.828943\n6787 11.919851 0.341291 0.207698 0.066398 0.484054 2.146111 9.946568\n6788 11.925974 0.324501 0.226395 0.076989 0.352182 2.182546 10.029236\n6789 11.931977 0.282082 0.276476 0.132580 0.042618 2.355217 10.225078\n6790 11.938527 0.245589 0.318839 0.197256 -0.192635 2.408481 10.284920\n6791 11.944126 0.224801 0.344217 0.235674 -0.276353 2.406775 10.282363\n6792 11.950161 0.206217 0.369415 0.271716 -0.295321 2.411827 10.279216\n6793 11.956122 0.171607 0.419522 0.332004 -0.048052 2.516485 10.098479\n6794 11.962085 0.158817 0.444004 0.357154 0.138733 2.592662 9.995213\n6795 11.968384 0.142734 0.488021 0.405981 0.328524 2.654052 9.913001\n6796 11.974711 0.146394 0.535309 0.458601 -0.167338 2.445781 10.137053\n6797 11.980348 0.144147 0.564413 0.484102 -0.443903 2.295455 10.207787\n6798 11.986729 0.097354 0.617974 0.533103 -0.495800 2.149720 9.908913\n6799 11.992419 0.049079 0.630667 0.560510 -0.208408 2.171679 9.688320\n6800 11.997348 -0.022431 0.621750 0.598136 0.290632 2.242036 9.736065\n6801 12.003464 -0.127384 0.556133 0.652966 0.819188 2.271992 10.292279\n6802 12.009529 -0.183386 0.493255 0.684112 0.957284 2.254196 10.602427\n6803 12.015583 -0.270847 0.315811 0.747385 0.927083 2.305161 10.843155\n6804 12.021698 -0.292182 0.256583 0.762206 0.888155 2.395119 10.739449\n6805 12.027701 -0.332917 0.117513 0.773930 0.800804 2.685147 10.388011\n6806 12.033639 -0.343207 0.059171 0.763716 0.830831 2.794756 10.293591\n6807 12.039717 -0.309067 -0.035882 0.713739 0.854417 2.944067 10.500006\n6808 12.045899 -0.245811 -0.076608 0.671310 0.542399 2.872052 10.657684\n6809 12.051945 -0.127164 -0.099033 0.609574 -0.066026 2.653365 10.518557\n6810 12.057892 -0.056190 -0.093033 0.575591 -0.330401 2.523780 10.221529\n6811 12.063741 0.079059 -0.026905 0.506347 -0.388796 2.325308 9.437354\n6812 12.069898 0.113620 0.006961 0.482401 -0.244990 2.195481 9.301723\n6813 12.076003 0.200688 0.124384 0.389219 0.319741 1.714978 9.225639\n6814 12.081975 0.239948 0.181198 0.337613 0.540228 1.624843 9.197379\n6815 12.088244 0.320792 0.295791 0.222238 0.769644 1.737182 9.062201\n6816 12.094066 0.363425 0.352825 0.160551 0.739626 1.773034 9.016810\n6817 12.100144 0.427963 0.471591 0.027537 0.526960 1.527239 9.034300\n6818 12.106191 0.444438 0.529875 -0.046388 0.416459 1.420056 9.077174\n6819 12.112300 0.450757 0.638777 -0.202867 0.307019 1.428703 9.190660\n6820 12.118296 0.449496 0.688387 -0.279643 0.293568 1.519477 9.305691\n6821 12.124341 0.441822 0.766156 -0.418505 0.216118 1.688671 9.389892\n6822 12.130322 0.436118 0.790967 -0.479618 0.147218 1.753667 9.303252\n6823 12.136487 0.416883 0.808974 -0.588836 0.059332 1.908258 9.154599\n6824 12.142586 0.399095 0.803087 -0.639487 0.087358 2.037813 9.191369\n6825 12.148513 0.357591 0.770930 -0.735840 0.289889 2.174662 9.556260\n6826 12.154595 0.340630 0.748071 -0.781980 0.430974 2.134578 9.828700\n6827 12.160552 0.314568 0.694314 -0.865790 0.475266 2.144058 10.378816\n6828 12.166541 0.292822 0.663830 -0.899820 0.427598 2.308152 10.655504\n6829 12.172637 0.233896 0.594173 -0.949445 0.480198 2.523394 10.935539\n6830 12.179137 0.137005 0.493536 -0.978667 0.643774 2.114623 11.124556\n6831 12.184760 0.068290 0.424786 -0.989385 0.667576 1.800405 11.226806\n6832 12.191175 -0.088770 0.260516 -0.997653 0.460967 1.422411 11.507361\n6833 12.196807 -0.172120 0.173234 -0.990304 0.282951 1.472490 11.574770\n6834 12.203067 -0.346350 0.004756 -0.950171 -0.183339 2.039517 11.398464\n6835 12.208991 -0.437872 -0.072462 -0.923284 -0.447047 2.320825 11.241921\n6836 12.215153 -0.620079 -0.209867 -0.882836 -0.803818 2.621829 10.959106\n6837 12.221071 -0.705813 -0.272060 -0.875533 -0.862797 2.674057 10.822762\n6838 12.227200 -0.856838 -0.394427 -0.880266 -0.670090 2.766749 10.539397\n6839 12.233084 -0.916606 -0.455433 -0.886522 -0.434233 2.837017 10.409848\n6840 12.239186 -1.008650 -0.572062 -0.894629 0.239824 2.792826 10.231451\n6841 12.245198 -1.051733 -0.624966 -0.893703 0.613776 2.580213 10.132792\n6842 12.251327 -1.161308 -0.715848 -0.890732 1.209967 2.085103 10.063023\n6843 12.257374 -1.228075 -0.752036 -0.894208 1.353492 1.904879 10.132868\n6844 12.263496 -1.376790 -0.796251 -0.916608 1.353256 1.652551 10.367848\n6845 12.269401 -1.453352 -0.804208 -0.933564 1.241393 1.524834 10.404674\n6846 12.275609 -1.592136 -0.795796 -0.968496 0.811718 1.270728 10.274645\n6847 12.281496 -1.651925 -0.780278 -0.984022 0.529312 1.271825 10.291877\n6848 12.287483 -1.744592 -0.722716 -1.013066 -0.069491 1.546430 10.438718\n6849 12.293381 -1.768901 -0.681071 -1.030432 -0.335364 1.656148 10.424003\n6850 12.299485 -1.778514 -0.582824 -1.082073 -0.806352 1.697411 10.403557\n6851 12.305641 -1.766392 -0.535021 -1.118055 -0.945701 1.808600 10.500601\n6852 12.311612 -1.692748 -0.448395 -1.195875 -0.859649 2.211710 10.656558\n6853 12.317792 -1.633796 -0.413357 -1.227895 -0.664580 2.355632 10.682837\n6854 12.323612 -1.482909 -0.377713 -1.261285 -0.175403 2.349360 10.656251\n6855 12.329734 -1.398393 -0.376069 -1.263775 0.023990 2.298961 10.651462\n6856 12.335651 -1.231115 -0.405592 -1.249620 0.335461 2.323284 10.923047\n6857 12.341735 -1.155658 -0.439571 -1.237816 0.485007 2.273481 10.928148\n6858 12.347698 -1.017479 -0.552446 -1.209121 0.716624 2.360859 11.032917\n6859 12.353914 -0.945512 -0.632409 -1.190649 0.761350 2.429774 11.280271\n6860 12.359949 -0.811231 -0.805924 -1.148342 0.796263 2.256922 11.405641\n6861 12.365911 -0.759594 -0.899273 -1.124242 0.732390 2.053037 11.296769\n6862 12.372140 -0.711300 -1.092258 -1.067208 0.446467 1.550237 10.754338\n6863 12.378156 -0.710420 -1.186365 -1.039602 0.310956 1.224981 10.716474\n6864 12.384166 -0.767100 -1.380819 -0.989118 0.101325 0.617001 11.089368\n6865 12.390049 -0.818825 -1.479719 -0.961362 0.064056 0.386709 11.209544\n6866 12.396109 -0.952926 -1.677124 -0.898129 0.078579 0.200473 11.643547\n6867 12.402124 -1.035724 -1.774992 -0.863083 0.078137 0.263248 11.790936\n6868 12.408172 -1.188514 -1.948723 -0.790977 0.192759 0.269236 11.740241\n6869 12.414245 -1.258891 -2.028279 -0.759838 0.292144 0.197635 11.815536\n6870 12.420288 -1.363403 -2.176132 -0.715539 0.567113 -0.024059 11.629023\n6871 12.426447 -1.378485 -2.240190 -0.700510 0.766304 -0.138147 11.493270\n6872 12.432448 -1.347261 -2.365240 -0.674519 1.202863 -0.126998 11.278768\n6873 12.438545 -1.305927 -2.423170 -0.662820 1.396280 -0.044859 10.994338\n6874 12.444414 -1.181730 -2.529802 -0.644623 1.741540 0.075664 10.536179\n6875 12.450693 -1.116869 -2.582655 -0.641304 1.842404 0.144190 10.474791\n6876 12.456543 -1.001514 -2.669175 -0.658426 1.852448 0.360408 10.519257\n6877 12.462523 -0.945112 -2.696678 -0.678701 1.827921 0.381439 10.565922\n6878 12.468615 -0.858877 -2.722263 -0.730945 1.896667 0.253274 10.397026\n6879 12.474673 -0.826643 -2.719009 -0.758912 1.994091 0.200260 10.205703\n6880 12.480634 -0.772126 -2.675586 -0.810912 2.215319 0.043493 9.886061\n6881 12.486806 -0.749070 -2.639287 -0.836065 2.346930 -0.142753 9.645460\n6882 12.492842 -0.709080 -2.543895 -0.890152 2.595806 -0.587701 9.208925\n6883 12.498862 -0.691588 -2.486755 -0.920722 2.730899 -0.771462 9.039150\n6884 12.504959 -0.661651 -2.353704 -0.984236 3.076845 -1.008597 8.936079\n6885 12.511070 -0.650049 -2.277535 -1.014728 3.202129 -1.109218 8.884645\n6886 12.517089 -0.629865 -2.105747 -1.070785 3.188824 -1.302624 8.826549\n6887 12.523034 -0.621123 -2.010854 -1.098980 3.091642 -1.373286 8.833836\n6888 12.529020 -0.601755 -1.801219 -1.165732 2.905367 -1.565268 8.905389\n6889 12.535211 -0.589503 -1.688243 -1.206375 2.847106 -1.742306 8.960609\n6890 12.541272 -0.561154 -1.449865 -1.302653 2.816428 -2.162214 9.006611\n6891 12.547722 -0.539735 -1.328565 -1.358184 2.835663 -2.182103 8.939832\n6892 12.553293 -0.485386 -1.103942 -1.472698 2.749722 -1.714048 8.914871\n6893 12.559767 -0.409481 -0.932640 -1.587250 2.332752 -0.946294 9.158779\n6894 12.565344 -0.357149 -0.878411 -1.647474 2.042909 -0.695379 9.300973\n6895 12.571798 -0.232094 -0.855094 -1.775592 1.669823 -0.756068 9.669127\n6896 12.577506 -0.171443 -0.889657 -1.841901 1.841827 -0.939462 9.794139\n6897 12.583953 -0.050175 -1.065261 -1.966737 3.418561 -1.226292 9.723026\n6898 12.589526 0.001065 -1.173828 -2.000110 4.436692 -1.220361 9.512259\n6899 12.595925 0.089023 -1.408892 -2.027675 6.105672 -1.123443 8.719291\n6900 12.603917 0.127817 -1.525562 -2.033452 6.495585 -1.188324 8.329627\n6901 12.607931 0.207989 -1.736854 -2.055197 6.382847 -1.386867 7.920738\n6902 12.613733 0.252359 -1.822995 -2.076991 6.056333 -1.371566 7.986502\n6903 12.619983 0.338879 -1.946325 -2.132894 5.163390 -0.941633 8.193557\n6904 12.625873 0.371108 -1.984723 -2.157634 4.708436 -0.657553 8.131588\n6905 12.631812 0.415498 -2.020941 -2.192836 3.995272 -0.354833 7.989685\n6906 12.637694 0.431529 -2.020302 -2.207374 3.836944 -0.316220 8.015742\n6907 12.644175 0.478229 -1.985423 -2.239741 3.905639 -0.286073 8.162161\n6908 12.649787 0.512740 -1.955053 -2.257732 3.965283 -0.245136 8.210611\n6909 12.656098 0.591789 -1.872920 -2.287088 3.825230 0.022108 8.026442\n6910 12.661871 0.627809 -1.820736 -2.291793 3.667598 0.284998 7.831257\n6911 12.668083 0.672765 -1.697455 -2.273437 3.316331 0.741329 7.395787\n6912 12.674038 0.679202 -1.628745 -2.254766 3.207705 0.799875 7.283276\n6913 12.680197 0.681158 -1.494722 -2.224117 3.194261 0.579196 7.352450\n6914 12.686096 0.682519 -1.436410 -2.219460 3.269316 0.453132 7.438492\n6915 12.692350 0.682305 -1.357273 -2.234790 3.550748 0.385998 7.458596\n6916 12.698143 0.675258 -1.342713 -2.251667 3.684912 0.492401 7.365340\n6917 12.704101 0.646362 -1.368299 -2.296927 3.816057 0.857199 7.269170\n6918 12.710382 0.624634 -1.405353 -2.325245 3.908438 1.004193 7.360187\n6919 12.716303 0.578915 -1.512819 -2.393571 4.400607 1.342213 7.629492\n6920 12.722351 0.569763 -1.575950 -2.429288 4.746423 1.648759 7.742249\n6921 12.728330 0.601447 -1.698577 -2.488037 5.132973 2.221382 7.757923\n6922 12.734532 0.639180 -1.751962 -2.508132 5.235754 2.317680 7.774887\n6923 12.740545 0.758911 -1.841268 -2.522333 5.370772 2.191449 7.542895\n6924 12.746618 0.827167 -1.873708 -2.513355 5.381495 2.087646 7.289431\n6925 12.752535 0.979241 -1.917587 -2.471037 5.256479 1.924493 6.799605\n6926 12.758519 1.056876 -1.920110 -2.441883 5.051996 1.957252 6.562540\n6927 12.764671 1.200571 -1.885188 -2.376016 4.601656 2.272259 6.022411\n6928 12.770678 1.259106 -1.860122 -2.347377 4.670632 2.435083 5.811854\n6929 12.777022 1.352466 -1.806958 -2.302389 4.886449 2.701749 5.903162\n6930 12.782786 1.382716 -1.781041 -2.283257 4.802082 2.751259 6.166672\n6931 12.788903 1.385360 -1.735616 -2.254336 4.376379 2.899336 6.445184\n6932 12.794882 1.351529 -1.719553 -2.241903 4.083172 3.085221 6.336355\n6933 12.800984 1.229930 -1.714578 -2.217620 3.952670 3.296238 6.280572\n6934 12.806864 1.154983 -1.728778 -2.214019 4.120298 3.218762 6.463803\n6935 12.812977 1.010719 -1.786848 -2.229649 4.789824 2.853095 6.790947\n6936 12.818996 0.947741 -1.831953 -2.245003 5.250318 2.674669 6.764940\n6937 12.825152 0.847150 -1.931760 -2.273736 6.039880 2.822777 6.439699\n6938 12.831081 0.814123 -1.968161 -2.278916 6.307459 3.200670 6.204068\n6939 12.837194 0.773984 -1.985340 -2.264504 6.581755 3.962420 5.546428\n6940 12.843508 0.771686 -1.967328 -2.249786 6.609848 4.083787 5.227038\n6941 12.849199 0.821203 -1.890862 -2.217218 6.726588 4.184489 4.896377\n6942 12.855293 0.875869 -1.844214 -2.198724 6.874474 4.330948 4.874236\n6943 12.861320 1.038182 -1.759496 -2.139702 7.210356 4.912889 4.816849\n6944 12.867600 1.130102 -1.721485 -2.094363 7.278873 5.220410 4.752619\n6945 12.873396 1.296822 -1.660275 -1.981091 7.074158 5.503656 4.659844\n6946 12.879392 1.357390 -1.637227 -1.922666 6.879301 5.507582 4.636907\n6947 12.885465 1.419133 -1.609083 -1.820500 6.571201 5.549764 4.796028\n6948 12.891457 1.426505 -1.605379 -1.777771 6.420328 5.651032 4.962860\n6949 12.897636 1.408127 -1.599950 -1.702331 6.395560 6.078351 4.887851\n6950 12.903470 1.373462 -1.597522 -1.666193 6.649112 6.335446 4.490126\n6951 12.909807 1.249006 -1.603377 -1.583926 7.315905 6.677492 3.560852\n6952 12.915742 1.174630 -1.598605 -1.537134 7.525489 6.763850 3.432239\n6953 12.921998 1.021638 -1.537747 -1.449993 7.558061 6.984724 3.514785\n6954 12.927771 0.946919 -1.479333 -1.407950 7.440546 7.125188 3.331510\n6955 12.933797 0.802649 -1.307256 -1.316610 7.335876 7.469963 2.580880\n6956 12.939947 0.739988 -1.198902 -1.268918 7.336780 7.698272 2.290465\n6957 12.945917 0.638838 -0.947636 -1.164758 7.315799 8.075336 1.995211\n6958 12.952352 0.597959 -0.808358 -1.108230 7.365073 8.096024 1.982385\n6959 12.958031 0.521517 -0.521224 -0.995722 7.430947 7.828280 2.112437\n6960 12.964569 0.480674 -0.376424 -0.939676 7.407070 7.662980 2.185986\n6961 12.970029 0.363501 -0.049713 -0.811147 7.514770 7.458635 2.248415\n6962 12.976932 0.231298 0.239271 -0.690572 7.576774 7.570189 2.158977\n6963 12.982240 0.165917 0.383981 -0.623611 7.461387 7.692301 2.186464\n6964 12.988646 0.047466 0.674311 -0.476687 6.980892 7.951866 2.378047\n6965 12.994252 -0.008608 0.817704 -0.397339 6.734944 8.103979 2.464673\n6966 13.000580 -0.123277 1.082604 -0.219392 6.524448 8.384696 2.501698\n6967 13.006272 -0.183715 1.199157 -0.120617 6.577740 8.506857 2.565270\n6968 13.012760 -0.309645 1.399362 0.094853 6.771480 8.609757 2.820769\n6969 13.018507 -0.374154 1.482607 0.211034 6.886701 8.594987 2.849457\n6970 13.024631 -0.498501 1.616037 0.452349 7.102330 8.531742 2.758988\n6971 13.030631 -0.551321 1.665127 0.573097 7.184796 8.522123 2.809205\n6972 13.036754 -0.636060 1.750147 0.803427 7.317843 8.515455 3.038761\n6973 13.042793 -0.669854 1.792350 0.907852 7.346013 8.474379 3.112991\n6974 13.048872 -0.729365 1.885144 1.090219 7.224048 8.309365 3.167900\n6975 13.054718 -0.756711 1.939880 1.168109 7.082273 8.241439 3.238227\n6976 13.060855 -0.800206 2.063241 1.300552 6.770006 8.143377 3.464211\n6977 13.066851 -0.809764 2.127976 1.357622 6.649397 8.144691 3.542060\n6978 13.073082 -0.789853 2.255116 1.456121 6.545842 8.332325 3.690550\n6979 13.078863 -0.765810 2.316000 1.497245 6.594840 8.452249 3.789115\n6980 13.085011 -0.703041 2.428109 1.568348 6.750923 8.691981 3.963601\n6981 13.090892 -0.668289 2.479104 1.599046 6.865700 8.733549 4.046729\n6982 13.096974 -0.607364 2.566226 1.657596 7.168018 8.677781 4.214620\n6983 13.104598 -0.582699 2.601106 1.690573 7.271784 8.638599 4.271544\n6984 13.109136 -0.537007 2.658580 1.770940 7.210896 8.495720 4.447133\n6985 13.115167 -0.516967 2.683736 1.816131 7.027829 8.338531 4.545255\n6986 13.121139 -0.501519 2.732650 1.912584 6.631358 7.838815 4.646778\n6987 13.127169 -0.512406 2.756214 1.962536 6.564657 7.586111 4.648628\n6988 13.133245 -0.577037 2.801845 2.065121 6.560351 7.248086 4.739314\n6989 13.139251 -0.629687 2.825494 2.117667 6.568766 7.090906 4.860028\n6990 13.145183 -0.762736 2.875103 2.223874 6.571672 6.734053 5.049932\n6991 13.151511 -0.832169 2.900589 2.277173 6.516732 6.640990 5.054007\n6992 13.157462 -0.943487 2.953286 2.381387 6.169017 6.626245 4.976179\n6993 13.163512 -0.981023 2.982611 2.428658 5.868350 6.609160 4.984965\n6994 13.169522 -1.025957 3.055376 2.508145 4.995651 6.561674 5.108740\n6995 13.175740 -1.035593 3.100838 2.540893 4.444125 6.575757 5.200999\n6996 13.181747 -1.015827 3.219548 2.597799 3.289320 6.509754 5.559133\n6997 13.187706 -1.000610 3.293520 2.622766 2.933042 6.338009 5.694339\n6998 13.193755 -0.951906 3.441813 2.671570 2.850389 5.875134 6.031524\n6999 13.199702 -0.917183 3.509309 2.696212 3.086154 5.704059 6.277953\n7000 13.205849 -0.823259 3.623397 2.738502 3.670552 5.658472 6.929044\n7001 13.211697 -0.776156 3.670202 2.756674 3.841402 5.702811 7.081455\n7002 13.217927 -0.697808 3.751135 2.786998 3.805196 5.627996 7.041199\n7003 13.223835 -0.677024 3.788027 2.794938 3.632707 5.427503 7.015490\n7004 13.229928 -0.674479 3.858551 2.795334 3.214194 4.841424 7.111534\n7005 13.235923 -0.687745 3.891829 2.790402 3.078004 4.591570 7.210659\n7006 13.242178 -0.735594 3.947168 2.777107 2.863651 4.226256 7.570452\n7007 13.248161 -0.773923 3.967968 2.769313 2.713395 4.089225 7.757312\n7008 13.253976 -0.885965 3.993402 2.744232 2.333900 3.919644 7.930032\n7009 13.260159 -0.962549 3.995555 2.723380 2.180220 3.840088 7.943641\n7010 13.266114 -1.154498 3.972485 2.662217 1.993111 3.612129 7.909735\n7011 13.272147 -1.259958 3.946376 2.623473 1.951965 3.463696 7.971407\n7012 13.278077 -1.468211 3.864982 2.531800 1.944778 3.128445 8.210192\n7013 13.284203 -1.562507 3.810804 2.481057 1.995458 2.971737 8.244167\n7014 13.290302 -1.721042 3.678320 2.378030 2.100686 2.710942 8.352238\n7015 13.296336 -1.791807 3.602357 2.326477 2.123733 2.587787 8.445813\n7016 13.302440 -1.916502 3.442309 2.215561 2.120036 2.425752 8.699762\n7017 13.308708 -1.967036 3.360512 2.155255 2.027000 2.330153 8.814660\n7018 13.314611 -2.042650 3.204403 2.039195 1.533168 1.947687 8.948063\n7019 13.320649 -2.061427 3.135008 1.987498 1.154638 1.768930 8.999395\n7020 13.326582 -2.066286 3.018167 1.903742 0.367825 1.821401 8.773892\n7021 13.332577 -2.055575 2.970017 1.875726 -0.007764 1.918026 8.514468\n7022 13.338777 -2.022396 2.891331 1.840485 -0.530422 1.715868 8.348073\n7023 13.344751 -2.002625 2.857397 1.820742 -0.643308 1.409035 8.458466\n7024 13.350746 -1.978748 2.830433 1.794380 -0.521672 1.062810 8.609402\n7025 13.357293 -1.967889 2.822636 1.783635 -0.321693 0.963957 8.598300\n7026 13.362862 -1.961192 2.822086 1.769350 0.290652 0.849031 8.401389\n7027 13.369483 -1.962047 2.826152 1.766317 0.444806 0.793539 8.321365\n7028 13.375083 -1.959124 2.837338 1.749136 0.538319 0.563310 8.023940\n7029 13.381431 -1.952555 2.845299 1.694027 0.293270 0.292021 7.968000\n7030 13.387026 -1.956063 2.849116 1.654080 0.162472 0.237656 7.922376\n7031 13.393619 -1.966774 2.857744 1.564815 -0.172501 0.386484 7.998631\n7032 13.399143 -1.981754 2.861610 1.516558 -0.376381 0.525726 8.072965\n7033 13.405632 -2.029516 2.869370 1.415552 -0.753142 0.638777 8.150245\n7034 13.411204 -2.063541 2.872202 1.362195 -0.801135 0.574636 8.166850\n7035 13.417577 -2.131312 2.866728 1.251273 -0.852432 0.213652 8.309951\n7036 13.423376 -2.162597 2.861456 1.195582 -0.908103 -0.058741 8.414838\n7037 13.429679 -2.219768 2.844908 1.084938 -0.859677 -0.620257 8.655466\n7038 13.435517 -2.243538 2.831029 1.039219 -0.919562 -0.797120 8.725388\n7039 13.441970 -2.280228 2.801189 0.978124 -1.132502 -1.017340 8.716115\n7040 13.447555 -2.292133 2.783589 0.954114 -1.199209 -1.169640 8.764700\n7041 13.453801 -2.292138 2.732264 0.911591 -1.559638 -1.531564 8.894055\n7042 13.459589 -2.277814 2.702954 0.890325 -1.707344 -1.721573 8.967627\n7043 13.465805 -2.216479 2.635589 0.837319 -1.921315 -1.917660 9.248750\n7044 13.471591 -2.174122 2.598705 0.812638 -2.074377 -1.876650 9.304382\n7045 13.477802 -2.073017 2.528558 0.770268 -2.338721 -1.820253 9.314513\n7046 13.483678 -2.020470 2.492055 0.745507 -2.429887 -1.901347 9.306683\n7047 13.489966 -1.921923 2.402815 0.685878 -2.585259 -2.220072 9.239889\n7048 13.495738 -1.874150 2.347089 0.646888 -2.585491 -2.438142 9.248879\n7049 13.501921 -1.781840 2.205935 0.543560 -2.555053 -2.922736 9.369841\n7050 13.508049 -1.743696 2.121617 0.487993 -2.630364 -3.151329 9.401503\n7051 13.514051 -1.698416 1.936517 0.384498 -2.861571 -3.516425 9.509235\n7052 13.519922 -1.692268 1.839919 0.338052 -3.003707 -3.622629 9.562188\n7053 13.526051 -1.704497 1.659282 0.259951 -3.195510 -3.826503 9.621491\n7054 13.532051 -1.716132 1.577602 0.224433 -3.216949 -3.999098 9.563470\n7055 13.538174 -1.730105 1.433428 0.152928 -3.230791 -4.263040 9.187289\n7056 13.544180 -1.725146 1.372277 0.120883 -3.254692 -4.274527 8.931147\n7057 13.550218 -1.687898 1.278921 0.073850 -3.285333 -4.318927 8.494640\n7058 13.556178 -1.660650 1.248668 0.059182 -3.294937 -4.370730 8.360442\n7059 13.562177 -1.600954 1.219929 0.046710 -3.315710 -4.381433 8.224403\n7060 13.568305 -1.562706 1.218434 0.048825 -3.258881 -4.329485 8.107347\n7061 13.574433 -1.440263 1.245116 0.033256 -3.540427 -4.402669 7.959668\n7062 13.580403 -1.398813 1.271749 0.008951 -3.902990 -4.489108 8.057655\n7063 13.586486 -1.294051 1.339849 -0.091308 -4.462313 -4.486524 7.686179\n7064 13.592476 -1.233686 1.379827 -0.157602 -4.586793 -4.418551 7.517254\n7065 13.598461 -1.136744 1.438088 -0.294847 -4.712324 -4.308537 7.455958\n7066 13.604463 -1.098014 1.458197 -0.362896 -4.857260 -4.303223 7.430192\n7067 13.610706 -1.015283 1.486347 -0.507158 -5.258042 -4.614782 7.459338\n7068 13.616690 -0.978544 1.487457 -0.590418 -5.512297 -4.910148 7.418137\n7069 13.622718 -0.915739 1.466609 -0.778569 -6.064728 -5.285389 7.392688\n7070 13.628767 -0.885013 1.446689 -0.876405 -6.295677 -5.245873 7.549468\n7071 13.634811 -0.830876 1.391270 -1.058784 -6.682971 -5.057435 7.741865\n7072 13.640990 -0.805748 1.359993 -1.138604 -6.917871 -5.101153 7.744699\n7073 13.646898 -0.757187 1.290441 -1.288393 -7.409304 -5.502803 7.673213\n7074 13.652909 -0.733800 1.251995 -1.366310 -7.588980 -5.733301 7.649732\n7075 13.658980 -0.673828 1.165786 -1.526816 -7.694625 -6.064622 7.698518\n7076 13.664884 -0.635832 1.118779 -1.603457 -7.613848 -6.158482 7.718225\n7077 13.670975 -0.552565 1.017032 -1.731229 -7.371697 -6.205987 7.647385\n7078 13.676917 -0.511145 0.964134 -1.776086 -7.234802 -6.187973 7.552104\n7079 13.682881 -0.430062 0.860823 -1.826289 -6.834286 -6.296735 7.548756\n7080 13.690803 -0.390475 0.811739 -1.837187 -6.613443 -6.469075 7.618247\n7081 13.695063 -0.307754 0.717778 -1.842842 -6.304438 -6.834772 7.767086\n7082 13.701153 -0.258229 0.672726 -1.837992 -6.255655 -6.945860 7.837630\n7083 13.707359 -0.136928 0.585399 -1.798079 -6.123480 -6.915661 7.837378\n7084 13.713484 -0.078991 0.552245 -1.761270 -6.046593 -6.885291 7.799612\n7085 13.719249 0.039784 0.497879 -1.651611 -5.914526 -6.957160 7.714091\n7086 13.725398 0.104636 0.474905 -1.587018 -5.893669 -6.993871 7.786066\n7087 13.731522 0.247790 0.428751 -1.448587 -5.924858 -7.032155 7.929354\n7088 13.737521 0.324033 0.403822 -1.374670 -5.903609 -7.066123 7.948561\n7089 13.743520 0.475662 0.342877 -1.217721 -5.849507 -7.117943 7.918087\n7090 13.749749 0.545163 0.306638 -1.133817 -5.855317 -7.096560 7.931134\n7091 13.755745 0.665257 0.224403 -0.958207 -5.809387 -7.069208 8.078108\n7092 13.761705 0.712797 0.178670 -0.869639 -5.765158 -7.118249 8.170256\n7093 13.767640 0.774939 0.075987 -0.698676 -5.730246 -7.350092 8.298549\n7094 13.774396 0.800747 -0.041615 -0.551025 -5.783991 -7.669638 8.293386\n7095 13.779797 0.805434 -0.104672 -0.487376 -5.820210 -7.783313 8.273178\n7096 13.785834 0.809310 -0.168314 -0.427950 -5.853596 -7.823495 8.273627\n7097 13.791798 0.827443 -0.289901 -0.315122 -5.963221 -7.641330 8.290846\n7098 13.798515 0.845023 -0.345459 -0.261350 -6.030991 -7.485982 8.285233\n7099 13.803892 0.904537 -0.448399 -0.163496 -6.120567 -7.335742 8.253655\n7100 13.810537 0.999620 -0.540917 -0.086157 -6.087562 -7.452415 8.305382\n7101 13.816075 1.060922 -0.584850 -0.057441 -6.041464 -7.512228 8.349435\n7102 13.822517 1.208769 -0.669661 -0.014917 -5.919416 -7.540601 8.428671\n7103 13.828168 1.293769 -0.710664 0.002764 -5.888826 -7.473186 8.508881\n7104 13.834548 1.479205 -0.789157 0.040429 -5.932417 -7.266733 8.663201\n7105 13.840296 1.576050 -0.826928 0.060709 -6.002691 -7.198279 8.741813\n7106 13.846548 1.770473 -0.902304 0.098969 -6.139758 -7.109841 8.858244\n7107 13.852337 1.866079 -0.940865 0.116916 -6.138555 -7.012535 8.865186\n7108 13.858663 2.046789 -1.021796 0.157351 -5.963372 -6.684746 8.769731\n7109 13.864300 2.129906 -1.064175 0.184456 -5.815023 -6.518272 8.702855\n7110 13.870588 2.284657 -1.149743 0.256313 -5.442556 -6.308125 8.630318\n7111 13.876425 2.356624 -1.191944 0.299843 -5.216561 -6.307334 8.658390\n7112 13.882666 2.482400 -1.271183 0.394917 -4.701184 -6.498528 8.727010\n7113 13.888525 2.537076 -1.306056 0.443681 -4.451484 -6.614997 8.746994\n7114 13.894638 2.629653 -1.362628 0.538742 -4.085289 -6.715607 8.810645\n7115 13.900488 2.669605 -1.383175 0.583514 -3.998479 -6.655831 8.867367\n7116 13.906749 2.751034 -1.402090 0.664949 -3.971178 -6.402596 9.021013\n7117 13.912655 2.798493 -1.400078 0.699508 -4.016836 -6.265245 9.094269\n7118 13.918699 2.913669 -1.378496 0.751828 -4.128236 -6.020216 9.056456\n7119 13.924837 2.983448 -1.362217 0.770208 -4.186125 -5.878247 8.952184\n7120 13.930800 3.145581 -1.326019 0.796515 -4.355202 -5.482605 8.666610\n7121 13.936798 3.233688 -1.308070 0.806942 -4.471018 -5.244546 8.559683\n7122 13.942959 3.418914 -1.281652 0.826980 -4.693614 -4.798978 8.459475\n7123 13.948921 3.513649 -1.275507 0.837816 -4.734622 -4.546004 8.507697\n7124 13.955045 3.696223 -1.281554 0.865796 -4.576978 -3.852616 8.954789\n7125 13.960960 3.778704 -1.292747 0.883778 -4.421328 -3.407113 9.309384\n7126 13.967091 3.916110 -1.325660 0.920593 -4.339245 -2.504704 9.934074\n7127 13.973171 3.969133 -1.345882 0.934242 -4.475135 -2.199154 10.039902\n7128 13.979049 4.042809 -1.394878 0.944886 -4.832800 -2.040410 9.837900\n7129 13.985150 4.061814 -1.425607 0.942503 -4.900926 -2.067671 9.641973\n7130 13.991063 4.084433 -1.500371 0.931763 -4.698870 -1.913358 9.383234\n7131 13.997269 4.094826 -1.543305 0.925847 -4.513942 -1.733669 9.348824\n7132 14.003284 4.109409 -1.638311 0.909187 -4.092838 -1.373661 9.348232\n7133 14.009358 4.107352 -1.688944 0.893723 -3.896883 -1.203384 9.281323\n7134 14.015438 4.085841 -1.791375 0.845248 -3.553626 -0.709054 9.031420\n7135 14.021358 4.070897 -1.840743 0.813120 -3.386243 -0.407672 8.952931\n7136 14.027320 4.037788 -1.932715 0.740184 -3.002395 0.028450 8.831548\n7137 14.033611 4.025655 -1.976979 0.703019 -2.769471 0.128960 8.733695\n7138 14.039728 4.014638 -2.064858 0.631815 -2.292310 0.273841 8.514899\n7139 14.045550 4.012679 -2.107530 0.595601 -2.095255 0.343675 8.411685\n7140 14.051503 4.003384 -2.180125 0.520166 -1.947428 0.452827 8.297887\n7141 14.057646 3.992332 -2.206880 0.480718 -1.974397 0.526098 8.260616\n7142 14.063797 3.961981 -2.236847 0.395517 -2.023218 0.868984 8.118917\n7143 14.069852 3.946514 -2.240641 0.351868 -1.994015 1.115618 8.011249\n7144 14.075799 3.921977 -2.233880 0.269902 -1.792720 1.531845 7.740094\n7145 14.081689 3.915679 -2.225889 0.231434 -1.651428 1.658796 7.611198\n7146 14.087812 3.920470 -2.204185 0.157516 -1.332043 1.914197 7.409729\n7147 14.093887 3.935055 -2.192115 0.123313 -1.157809 2.098987 7.300329\n7148 14.099916 3.991445 -2.164980 0.062363 -0.859765 2.464163 7.108101\n7149 14.106077 4.036637 -2.149364 0.037105 -0.755414 2.598467 7.015497\n7150 14.111963 4.162635 -2.114633 -0.000304 -0.640855 2.939690 6.921891\n7151 14.118048 4.240273 -2.095407 -0.011777 -0.594336 3.204218 6.859481\n7152 14.124039 4.413920 -2.056320 -0.015651 -0.458759 3.793094 6.538327\n7153 14.130139 4.507318 -2.040249 -0.006851 -0.341256 4.009836 6.271104\n7154 14.136127 4.706023 -2.022155 0.032273 0.064647 4.363623 5.792994\n7155 14.142111 4.779834 -2.022197 0.056598 0.312517 4.489798 5.670218\n7156 14.148096 4.889749 -2.034003 0.116431 0.856282 4.628015 5.448066\n7157 14.154247 4.917976 -2.046285 0.150550 1.074795 4.625565 5.341349\n7158 14.160222 4.902266 -2.083178 0.216686 1.259578 4.530424 5.185155\n7159 14.166246 4.858746 -2.106144 0.242609 1.291858 4.537078 5.149947\n7160 14.172601 4.717307 -2.158608 0.268616 1.289523 4.779675 5.095061\n7161 14.178577 4.627613 -2.186649 0.266484 1.281919 4.984192 5.029197\n7162 14.184508 4.437196 -2.240955 0.227153 1.109434 5.619741 4.876380\n7163 14.192192 4.341139 -2.260826 0.190953 0.912265 5.963909 4.645871\n7164 14.196552 4.152259 -2.279204 0.094018 0.626973 6.647879 3.884960\n7165 14.202591 4.058245 -2.280818 0.040364 0.550029 6.987377 3.499374\n7166 14.208682 3.884928 -2.261770 -0.058502 0.449955 7.569932 3.000767\n7167 14.214618 3.805725 -2.240694 -0.100010 0.443292 7.725780 2.843227\n7168 14.220743 3.655601 -2.182985 -0.160128 0.523910 7.928067 2.456566\n7169 14.227211 3.579416 -2.147059 -0.175782 0.619402 8.075994 2.197058\n7170 14.232804 3.420969 -2.065963 -0.178306 0.825912 8.550494 1.734824\n7171 14.239668 3.248341 -1.978366 -0.153569 0.973072 8.792921 1.464696\n7172 14.245159 3.159000 -1.933505 -0.137073 1.111454 8.757677 1.469115\n7173 14.251493 2.975979 -1.845999 -0.103690 1.454356 8.695839 1.634950\n7174 14.257161 2.884121 -1.802417 -0.086234 1.618244 8.716869 1.677083\n7175 14.263507 2.695745 -1.720235 -0.050528 1.970039 8.778038 1.699194\n7176 14.269233 2.599328 -1.682477 -0.033034 2.207228 8.880842 1.637699\n7177 14.275372 2.412472 -1.612722 0.000697 2.743968 9.311308 1.429192\n7178 14.281187 2.325596 -1.579403 0.016070 2.956731 9.579914 1.335550\n7179 14.287412 2.169162 -1.506808 0.038175 3.052909 10.132952 1.086853\n7180 14.293391 2.097802 -1.462948 0.045584 2.895791 10.361185 0.905764\n7181 14.299402 1.958072 -1.352903 0.058594 2.406447 10.542569 0.538381\n7182 14.305480 1.884946 -1.286489 0.066302 2.218425 10.597581 0.400068\n7183 14.311463 1.738246 -1.132701 0.092540 2.014771 10.802324 0.111458\n7184 14.317559 1.666406 -1.048996 0.112546 1.952712 10.877862 0.010210\n7185 14.323477 1.516599 -0.880414 0.158811 1.809380 10.746847 -0.104854\n7186 14.329444 1.437164 -0.798477 0.180745 1.797072 10.552459 -0.102853\n7187 14.335523 1.272035 -0.648057 0.218223 2.102759 10.093331 0.015225\n7188 14.341503 1.189612 -0.581484 0.234118 2.379772 9.814394 0.164327\n7189 14.347727 1.036622 -0.469231 0.258748 3.036794 9.218255 0.787019\n7190 14.353618 0.971297 -0.422105 0.266502 3.320590 9.008916 1.103910\n7191 14.359686 0.880595 -0.340805 0.266663 3.599069 8.914799 1.514284\n7192 14.365832 0.854626 -0.307168 0.255799 3.584871 9.035693 1.587388\n7193 14.371965 0.824883 -0.256062 0.206602 3.506063 9.588460 1.456174\n7194 14.377824 0.816687 -0.240039 0.170930 3.471205 9.930254 1.317887\n7195 14.383858 0.800434 -0.232346 0.087999 3.381568 10.375992 1.026392\n7196 14.389946 0.789711 -0.240055 0.044463 3.272361 10.472266 0.912422\n7197 14.396071 0.752780 -0.271725 -0.034676 2.834491 10.493471 0.813692\n7198 14.401883 0.721216 -0.290663 -0.068080 2.600610 10.369973 0.765393\n7199 14.408094 0.612522 -0.329550 -0.126829 2.289380 9.926127 0.740398\n7200 14.414216 0.538118 -0.352429 -0.153096 2.237271 9.711203 0.834958\n7201 14.420056 0.369709 -0.402158 -0.202945 2.420819 9.415159 1.153744\n7202 14.426107 0.285956 -0.431690 -0.227756 2.597148 9.355727 1.318048\n7203 14.432195 0.130503 -0.503465 -0.274565 2.859478 9.418612 1.392566\n7204 14.438355 0.063025 -0.542127 -0.296747 2.937723 9.529409 1.350439\n7205 14.444231 -0.042166 -0.620138 -0.339608 3.106563 9.922453 1.158166\n7206 14.450322 -0.079898 -0.657514 -0.358845 3.186236 10.197305 1.004383\n7207 14.456324 -0.138391 -0.720584 -0.393038 3.159997 10.668746 0.749284\n7208 14.462305 -0.165642 -0.743727 -0.409028 3.072900 10.760496 0.681144\n7209 14.468364 -0.218588 -0.768474 -0.436702 2.968937 10.689536 0.612090\n7210 14.474394 -0.244573 -0.769187 -0.444883 2.954947 10.631871 0.611899\n7211 14.480541 -0.306775 -0.750211 -0.443368 2.997356 10.585351 0.504157\n7212 14.486584 -0.346256 -0.732305 -0.433197 3.055073 10.626834 0.424910\n7213 14.492545 -0.443290 -0.684008 -0.399777 3.196648 10.841388 0.265093\n7214 14.498522 -0.500340 -0.654182 -0.380588 3.264982 10.992105 0.174789\n7215 14.504645 -0.627870 -0.589586 -0.347760 3.384242 11.348105 -0.173701\n7216 14.510553 -0.693608 -0.555579 -0.335313 3.397075 11.566191 -0.360377\n7217 14.516651 -0.836771 -0.482191 -0.315873 3.518357 11.985065 -0.662752\n7218 14.522741 -0.912206 -0.440765 -0.307055 3.630043 12.185412 -0.733838\n7219 14.528842 -1.076680 -0.348824 -0.288420 3.893885 12.375548 -0.885187\n7220 14.534760 -1.167158 -0.299816 -0.280486 3.953716 12.316855 -0.969038\n7221 14.540932 -1.368767 -0.191533 -0.270669 3.821392 11.932335 -0.995829\n7222 14.546954 -1.476089 -0.131153 -0.269320 3.737536 11.700904 -0.899570\n7223 14.552931 -1.692268 0.006475 -0.266654 3.483788 11.386586 -0.515163\n7224 14.558941 -1.800391 0.085144 -0.262561 3.365735 11.281190 -0.432909\n7225 14.565140 -2.011417 0.257585 -0.245216 3.081914 11.238305 -0.451514\n7226 14.571209 -2.119420 0.348734 -0.231255 2.847927 11.298762 -0.532558\n7227 14.577208 -2.339415 0.534728 -0.203380 2.352600 11.428799 -0.701529\n7228 14.583173 -2.452407 0.623237 -0.192855 2.179393 11.474834 -0.753060\n7229 14.589296 -2.678538 0.774019 -0.176951 2.075401 11.601304 -0.787146\n7230 14.595293 -2.791382 0.834659 -0.169769 2.123125 11.658993 -0.707855\n7231 14.601334 -3.017979 0.928693 -0.152016 2.292129 11.567515 -0.384971\n7232 14.607217 -3.131889 0.966208 -0.140645 2.362293 11.362059 -0.148102\n7233 14.613312 -3.359858 1.033581 -0.118678 2.426402 10.691781 0.388492\n7234 14.619501 -3.469548 1.067696 -0.110956 2.424275 10.360752 0.634321\n7235 14.625445 -3.659000 1.143721 -0.098900 2.315376 9.858901 1.142703\n7236 14.631955 -3.729439 1.187610 -0.092579 2.212099 9.676707 1.399384\n7237 14.637835 -3.811229 1.288726 -0.073283 1.880328 9.410858 1.824256\n7238 14.644169 -3.824889 1.395667 -0.038026 1.455677 9.207743 2.023659\n7239 14.649669 -3.815509 1.446739 -0.015158 1.251700 9.120604 2.090337\n7240 14.656042 -3.788923 1.531969 0.038962 0.942235 8.885048 2.347617\n7241 14.661828 -3.778876 1.561905 0.069628 0.896311 8.674154 2.566435\n7242 14.668020 -3.777132 1.588431 0.135232 0.984088 8.143005 3.176048\n7243 14.673813 -3.788174 1.583728 0.170184 1.027422 7.951491 3.503465\n7244 14.680205 -3.837326 1.545313 0.243980 0.933584 7.762916 4.112978\n7245 14.685918 -3.879365 1.515363 0.280410 0.801231 7.679649 4.418338\n7246 14.692151 -4.001876 1.438645 0.343589 0.507047 7.400196 4.945034\n7247 14.697950 -4.079622 1.392719 0.368073 0.435648 7.201255 5.158123\n7248 14.704210 -4.250043 1.289579 0.403178 0.478901 6.726444 5.553555\n7249 14.710021 -4.331654 1.235845 0.417243 0.516162 6.468460 5.770008\n7250 14.716194 -4.465941 1.137017 0.447055 0.423989 5.785976 6.281228\n7251 14.722152 -4.515178 1.097521 0.463738 0.266716 5.330004 6.547203\n7252 14.728194 -4.580325 1.045628 0.498315 -0.017676 4.378121 7.031459\n7253 14.734235 -4.598466 1.032346 0.515415 -0.058600 3.952969 7.252985\n7254 14.740305 -4.607763 1.023544 0.546261 -0.014915 3.345998 7.805075\n7255 14.746165 -4.597244 1.023492 0.557137 0.094569 3.156502 8.118083\n7256 14.752263 -4.541071 1.017256 0.567784 0.526248 2.982486 8.544619\n7257 14.758331 -4.497130 1.005998 0.568753 0.825278 3.007702 8.564462\n7258 14.764536 -4.388190 0.960519 0.562506 1.390180 3.133453 8.371577\n7259 14.770756 -4.327451 0.928091 0.553432 1.569082 3.140496 8.246597\n7260 14.776465 -4.199915 0.856794 0.518365 1.696321 2.941506 8.174114\n7261 14.782488 -4.134986 0.824150 0.492136 1.721708 2.749593 8.206668\n7262 14.788625 -4.004853 0.778212 0.430477 1.703993 2.290794 8.340246\n7263 14.794594 -3.942553 0.767871 0.399823 1.619733 2.047836 8.440475\n7264 14.800622 -3.832452 0.772296 0.346637 1.191885 1.478763 8.765251\n7265 14.806613 -3.788938 0.784906 0.323752 0.876613 1.106689 8.992327\n7266 14.812918 -3.732761 0.818827 0.279984 0.338831 0.306207 9.463054\n7267 14.818769 -3.720971 0.834026 0.258333 0.170637 -0.005945 9.683394\n7268 14.824889 -3.723955 0.852598 0.220598 0.002908 -0.351620 10.116433\n7269 14.830979 -3.735442 0.854344 0.205020 -0.058939 -0.410688 10.302834\n7270 14.837205 -3.765669 0.841783 0.177127 -0.237791 -0.455912 10.503069\n7271 14.843104 -3.778472 0.828311 0.162652 -0.289964 -0.580631 10.521337\n7272 14.848965 -3.787783 0.787037 0.127180 -0.203731 -0.918188 10.580091\n7273 14.855103 -3.779557 0.761701 0.107607 -0.155390 -0.928420 10.630388\n7274 14.861062 -3.742480 0.711183 0.073083 -0.250161 -0.681878 10.645032\n7275 14.867004 -3.707727 0.680281 0.055351 -0.388640 -0.561524 10.536103\n7276 14.873166 -3.646500 0.636741 0.029598 -0.540146 -0.684448 10.343007\n7277 14.879214 -3.605086 0.609754 0.010102 -0.523115 -0.897059 10.331308\n7278 14.885238 -3.494730 0.542141 -0.054466 -0.137914 -1.510163 10.361402\n7279 14.891212 -3.450469 0.519214 -0.080229 0.028827 -1.649688 10.382150\n7280 14.897318 -3.315746 0.467342 -0.149330 0.229993 -1.768435 10.330776\n7281 14.903559 -3.242738 0.449495 -0.183902 0.172913 -1.799343 10.267143\n7282 14.909348 -3.093424 0.429939 -0.260749 -0.057150 -2.061671 10.173274\n7283 14.915285 -3.009061 0.427367 -0.305894 -0.160119 -2.306937 10.220695\n7284 14.921513 -2.803937 0.433895 -0.410761 -0.281315 -2.815476 10.590167\n7285 14.927612 -2.651162 0.443968 -0.476845 -0.230946 -3.120502 10.691886\n7286 14.933632 -2.411536 0.457679 -0.549422 0.125045 -3.560346 10.563221\n7287 14.939512 -2.268806 0.462567 -0.573289 0.349243 -3.727367 10.428654\n7288 14.945623 -1.946216 0.468369 -0.585667 0.478437 -3.732495 10.255288\n7289 14.951614 -1.804282 0.467695 -0.582265 0.393608 -3.671110 10.255552\n7290 14.957690 -1.528839 0.452437 -0.580830 0.240241 -3.697416 10.258746\n7291 14.963793 -1.398085 0.436969 -0.587458 0.201750 -3.763263 10.275794\n7292 14.969948 -1.166901 0.392308 -0.612971 0.106191 -3.891389 10.337605\n7293 14.975821 -1.071363 0.365194 -0.628253 0.039138 -3.965507 10.383022\n7294 14.981882 -0.923835 0.309150 -0.661591 -0.185344 -4.137175 10.529555\n7295 14.988084 -0.868575 0.280460 -0.683293 -0.380643 -4.197413 10.597400\n7296 14.994010 -0.778289 0.220085 -0.751260 -0.942091 -4.235306 10.610188\n7297 15.000206 -0.736342 0.187334 -0.798885 -1.262594 -4.194665 10.569941\n7298 15.006202 -0.645433 0.117453 -0.909977 -1.676544 -4.004426 10.374037\n7299 15.012178 -0.594376 0.080317 -0.966043 -1.675874 -3.907095 10.254342\n7300 15.018331 -0.479468 0.002903 -1.064046 -1.296793 -3.828574 10.078521\n7301 15.024323 -0.418082 -0.035567 -1.102505 -1.009116 -3.863013 10.078051\n7302 15.030371 -0.294419 -0.107955 -1.161629 -0.553608 -3.890217 10.181207\n7303 15.037077 -0.171758 -0.168875 -1.212291 -0.469901 -3.747875 10.279675\n7304 15.042389 -0.111182 -0.193946 -1.240919 -0.473642 -3.718431 10.282445\n7305 15.048722 0.008605 -0.233324 -1.309457 -0.420876 -3.853309 10.183795\n7306 15.054481 0.067178 -0.248522 -1.347612 -0.346963 -3.956277 10.122168\n7307 15.061044 0.185839 -0.266781 -1.427676 -0.130699 -4.124970 10.069726\n7308 15.066522 0.247670 -0.268808 -1.470614 -0.010061 -4.244218 10.065937\n7309 15.072852 0.373195 -0.262086 -1.569916 0.198718 -4.642621 10.034157\n7310 15.078640 0.436839 -0.254921 -1.630726 0.266352 -4.850101 10.008307\n7311 15.084898 0.570201 -0.234230 -1.778634 0.347296 -5.047859 9.991050\n7312 15.090592 0.641042 -0.220759 -1.862771 0.367083 -5.039144 9.980967\n7313 15.096974 0.790441 -0.187799 -2.039490 0.394092 -4.978518 9.898429\n7314 15.102792 0.866266 -0.168958 -2.128175 0.400356 -4.914474 9.865068\n7315 15.109111 1.016260 -0.128680 -2.301645 0.321440 -4.658969 9.840809\n7316 15.114850 1.090959 -0.107877 -2.387914 0.216793 -4.481822 9.869487\n7317 15.120958 1.247596 -0.067680 -2.565084 -0.146169 -4.061901 9.998026\n7318 15.126944 1.331659 -0.048920 -2.656422 -0.363267 -3.787301 10.074723\n7319 15.133102 1.519738 -0.015850 -2.837702 -0.698283 -2.998604 10.113011\n7320 15.139068 1.626107 -0.004197 -2.922555 -0.783828 -2.483898 10.130654\n7321 15.145106 1.869992 0.001088 -3.066198 -0.790898 -1.541366 10.271307\n7322 15.151034 2.008912 -0.008827 -3.122577 -0.698072 -1.217527 10.389986\n7323 15.157074 2.301104 -0.062046 -3.203654 -0.424713 -0.946580 10.644788\n7324 15.163251 2.442142 -0.106958 -3.227252 -0.310030 -1.023221 10.701268\n7325 15.169270 2.678993 -0.236583 -3.235683 -0.247875 -1.411096 10.808486\n7326 15.175256 2.769041 -0.322232 -3.217987 -0.285719 -1.592806 10.947834\n7327 15.181280 2.895619 -0.527067 -3.139726 -0.332704 -1.888507 11.405247\n7328 15.187358 2.930808 -0.643664 -3.084898 -0.282626 -2.089314 11.655724\n7329 15.193514 2.948692 -0.898194 -2.964151 -0.024792 -2.597249 11.838869\n7330 15.199422 2.937894 -1.029341 -2.906250 0.143710 -2.838015 11.797301\n7331 15.205528 2.898328 -1.279736 -2.808611 0.528139 -2.872779 11.572025\n7332 15.211520 2.880792 -1.390778 -2.770039 0.710978 -2.521718 11.347999\n7333 15.217485 2.881704 -1.574011 -2.706684 0.843761 -1.329549 10.804817\n7334 15.223580 2.907087 -1.645844 -2.682082 0.789249 -0.714396 10.511156\n7335 15.229711 3.003315 -1.752856 -2.653961 0.508519 0.355036 9.815487\n7336 15.235849 3.063075 -1.792320 -2.649364 0.340108 0.859122 9.495179\n7337 15.241782 3.177672 -1.847881 -2.650480 0.181951 1.809007 9.041178\n7338 15.247815 3.225443 -1.862897 -2.649898 0.221899 2.228502 8.945599\n7339 15.253824 3.280117 -1.874510 -2.629861 0.569757 2.764091 8.894904\n7340 15.259755 3.286040 -1.874095 -2.608033 0.842123 2.826432 8.909690\n7341 15.265914 3.260877 -1.860969 -2.547466 1.320105 2.727002 9.057425\n7342 15.271974 3.235271 -1.847177 -2.512799 1.435006 2.701404 9.153786\n7343 15.277925 3.172707 -1.805431 -2.440078 1.514541 2.696169 9.194213\n7344 15.283979 3.138505 -1.776017 -2.404374 1.641477 2.638552 9.148450\n7345 15.290077 3.077568 -1.708174 -2.329208 1.995270 2.590564 9.018570\n7346 15.295967 3.054006 -1.669800 -2.287227 2.295659 2.614773 8.970010\n7347 15.302204 3.035622 -1.589874 -2.188622 2.659329 2.896867 8.930984\n7348 15.308169 3.033680 -1.551764 -2.130013 2.723411 3.167331 8.837165\n7349 15.314118 3.041630 -1.486601 -1.995984 2.457704 3.808490 8.717411\n7350 15.320235 3.045033 -1.459801 -1.920199 2.165845 4.133580 8.659435\n7351 15.326333 3.045239 -1.420165 -1.750732 1.664511 4.740942 8.564754\n7352 15.332312 3.038600 -1.408244 -1.655915 1.455986 5.028867 8.520686\n7353 15.338313 3.012219 -1.396403 -1.443704 1.148549 5.489648 8.454583\n7354 15.344441 2.993620 -1.397150 -1.330310 1.111458 5.624256 8.409484\n7355 15.350531 2.948371 -1.411067 -1.099717 0.986519 5.760246 8.366926\n7356 15.356524 2.921386 -1.422569 -0.987954 0.877236 5.765107 8.412565\n7357 15.362649 2.867581 -1.453044 -0.791776 0.538200 5.455075 8.521472\n7358 15.369231 2.840607 -1.471261 -0.711148 0.357205 5.196604 8.607990\n7359 15.374702 2.789785 -1.516253 -0.583219 0.334258 4.730414 8.855173\n7360 15.380650 2.768122 -1.542896 -0.534525 0.457752 4.660677 8.946006\n7361 15.386623 2.743913 -1.604658 -0.457264 0.681517 4.867500 8.924131\n7362 15.393136 2.742302 -1.640934 -0.426799 0.787249 5.016131 8.805090\n7363 15.398818 2.749955 -1.724752 -0.386378 1.076312 5.377209 8.228790\n7364 15.405278 2.759759 -1.834396 -0.373542 1.810587 5.919317 7.352461\n7365 15.410912 2.765960 -1.903378 -0.371803 2.143884 6.301836 7.038869\n7366 15.417274 2.773931 -2.047741 -0.359446 2.363737 6.975585 6.700552\n7367 15.422941 2.775283 -2.117617 -0.344175 2.323149 7.219460 6.574887\n7368 15.429250 2.745011 -2.250721 -0.287819 2.188464 7.589540 5.920986\n7369 15.435308 2.702265 -2.328789 -0.237076 2.284643 7.749189 5.614445\n7370 15.441244 2.616047 -2.432935 -0.162256 2.611557 7.758831 5.535285\n7371 15.447168 2.557124 -2.488547 -0.121901 2.749207 7.671201 5.591547\n7372 15.453399 2.425668 -2.610019 -0.037354 2.956209 7.392081 5.861141\n7373 15.459282 2.366901 -2.661596 -0.000471 3.015687 7.372974 5.872160\n7374 15.465413 2.271307 -2.761146 0.078195 2.934615 7.531344 5.744863\n7375 15.471434 2.229524 -2.808719 0.115600 2.878696 7.601686 5.658389\n7376 15.477512 2.173696 -2.906283 0.156787 2.847243 7.604032 5.655357\n7377 15.483442 2.159423 -2.954150 0.157129 2.926432 7.619434 5.592582\n7378 15.489606 2.164565 -3.053020 0.127877 3.337562 7.736881 5.247203\n7379 15.495436 2.178119 -3.102519 0.108869 3.558570 7.772149 4.999195\n7380 15.501607 2.210291 -3.194459 0.088108 3.771557 7.665971 4.484348\n7381 15.507454 2.228259 -3.235234 0.089774 3.766436 7.516436 4.361177\n7382 15.513471 2.255125 -3.306350 0.111364 3.677915 7.253020 4.225619\n7383 15.519552 2.260295 -3.334262 0.130319 3.651132 7.271867 4.144789\n7384 15.525658 2.257520 -3.377398 0.181747 3.760031 7.564522 3.784784\n7385 15.531524 2.246740 -3.391980 0.213228 3.894247 7.786860 3.421401\n7386 15.537852 2.222827 -3.411276 0.291487 4.152016 8.296351 2.600152\n7387 15.543812 2.210357 -3.415569 0.339019 4.290091 8.542137 2.216543\n7388 15.549781 2.205359 -3.410600 0.442314 4.517065 8.802152 1.838158\n7389 15.555920 2.207957 -3.399027 0.495931 4.603414 8.767200 1.786989\n7390 15.561967 2.208613 -3.358132 0.596904 4.779333 8.445132 1.723926\n7391 15.568149 2.196133 -3.327881 0.642659 4.814900 8.256749 1.702753\n7392 15.573972 2.145510 -3.246566 0.729112 4.748403 7.946425 1.673935\n7393 15.580062 2.109808 -3.193148 0.770345 4.686161 7.843088 1.685484\n7394 15.586012 2.031087 -3.059917 0.847591 4.497591 7.779290 1.635263\n7395 15.592003 1.998560 -2.980010 0.884840 4.396621 7.734155 1.593874\n7396 15.598148 1.941928 -2.792393 0.955786 4.140594 7.611737 1.420952\n7397 15.604197 1.915037 -2.686812 0.990754 3.930772 7.603381 1.255498\n7398 15.610355 1.854641 -2.457546 1.073228 3.648881 7.610651 0.909400\n7399 15.616249 1.821924 -2.338077 1.124764 3.693287 7.612514 0.778377\n7400 15.622401 1.766944 -2.111453 1.256246 4.064727 7.662041 0.344277\n7401 15.628354 1.743588 -2.014640 1.335836 4.393696 7.724408 0.143273\n7402 15.634515 1.715285 -1.874948 1.504005 5.267768 7.735014 -0.246510\n7403 15.640395 1.719727 -1.832766 1.585186 5.671274 7.794823 -0.400963\n7404 15.646490 1.748804 -1.789117 1.731479 6.218194 8.088630 -0.565198\n7405 15.652479 1.769569 -1.778773 1.793096 6.364084 8.178144 -0.669806\n7406 15.658451 1.817375 -1.764235 1.891742 6.422837 8.090678 -0.947039\n7407 15.664606 1.844304 -1.759209 1.929433 6.398445 7.962361 -1.067177\n7408 15.670695 1.906305 -1.748763 1.977658 6.278563 7.666224 -1.084053\n7409 15.676650 1.944367 -1.739764 1.988988 6.107141 7.467510 -1.014962\n7410 15.682675 2.034767 -1.705915 1.992917 5.574823 6.893718 -1.007191\n7411 15.688604 2.081775 -1.681763 1.986658 5.308185 6.609983 -1.029980\n7412 15.694795 2.174640 -1.623330 1.964452 4.971411 6.261739 -0.853755\n7413 15.700992 2.224517 -1.590172 1.951940 4.964424 6.141458 -0.697906\n7414 15.706766 2.346899 -1.526079 1.926151 5.216579 5.868815 -0.501312\n7415 15.712705 2.423283 -1.498379 1.912597 5.443226 5.733364 -0.615839\n7416 15.718941 2.595519 -1.449043 1.881871 6.021901 5.701239 -1.299044\n7417 15.725021 2.684761 -1.425607 1.863922 6.337955 5.856102 -1.707512\n7418 15.730980 2.840134 -1.369711 1.823792 6.840844 6.311932 -2.556659\n7419 15.737065 2.895361 -1.336828 1.800948 6.921293 6.533133 -2.936155\n7420 15.743022 2.949863 -1.267485 1.749281 6.713652 6.481464 -3.489352\n7421 15.749133 2.947767 -1.228023 1.725230 6.570951 6.190416 -3.541929\n7422 15.755215 2.891144 -1.129315 1.699817 6.445683 5.552487 -3.345239\n7423 15.761078 2.846377 -1.065262 1.704512 6.516247 5.275036 -3.295421\n7424 15.767477 2.748697 -0.910966 1.748372 6.785438 4.864612 -3.383796\n7425 15.773224 2.703351 -0.824957 1.782116 6.880597 4.755668 -3.531248\n7426 15.779478 2.639386 -0.641832 1.854324 7.068933 4.829549 -3.986299\n7427 15.785473 2.627351 -0.550209 1.890036 7.183004 4.980125 -4.241044\n7428 15.791518 2.651645 -0.376438 1.961150 7.490872 5.323164 -4.633530\n7429 15.798019 2.682731 -0.293631 1.996984 7.619123 5.458506 -4.775206\n7430 15.803555 2.752318 -0.141952 2.075905 7.771458 5.599529 -4.918255\n7431 15.810050 2.807019 -0.016947 2.169119 8.025990 5.476025 -4.837443\n7432 15.815567 2.825620 0.035634 2.218184 8.141198 5.274407 -4.732488\n7433 15.822144 2.838930 0.118247 2.312497 8.251208 4.728293 -4.446950\n7434 15.827643 2.834625 0.151323 2.355549 8.338048 4.528181 -4.297655\n7435 15.834246 2.798517 0.205482 2.433956 8.510765 4.174845 -4.032553\n7436 15.839754 2.769047 0.224697 2.469065 8.463405 4.038465 -4.043203\n7437 15.846188 2.680591 0.242875 2.512299 8.138315 3.722387 -4.175004\n7438 15.851934 2.624665 0.243788 2.514320 7.984251 3.535728 -4.187019\n7439 15.858226 2.508398 0.244578 2.479754 7.897715 3.151811 -4.119400\n7440 15.863993 2.448435 0.250411 2.445011 7.970857 2.955629 -4.119617\n7441 15.870097 2.332807 0.278934 2.351763 8.141005 2.545776 -4.414576\n7442 15.875948 2.278720 0.303626 2.298766 8.223899 2.344547 -4.620012\n7443 15.882128 2.168149 0.383920 2.167440 8.534083 1.881071 -4.880803\n7444 15.888124 2.129863 0.428096 2.101667 8.725800 1.669956 -4.945698\n7445 15.894260 2.088944 0.526004 1.957446 9.089013 1.347362 -5.106422\n7446 15.900388 2.089164 0.578126 1.880350 9.170989 1.245568 -5.188100\n7447 15.906416 2.126422 0.690178 1.721334 9.119371 1.071796 -5.260171\n7448 15.912236 2.157237 0.749636 1.640392 9.067440 0.963319 -5.235465\n7449 15.918424 2.226653 0.863151 1.482807 9.177505 0.736239 -5.141580\n7450 15.924261 2.262275 0.911151 1.405996 9.356852 0.635153 -5.057860\n7451 15.930234 2.329769 0.976297 1.261123 9.740827 0.529565 -4.823812\n7452 15.936289 2.361216 0.993072 1.195172 9.835272 0.468279 -4.704033\n7453 15.942347 2.412864 1.005775 1.081193 9.735989 0.353549 -4.445374\n7454 15.948528 2.428589 1.008222 1.035927 9.588855 0.317828 -4.358918\n7455 15.954511 2.427886 1.017999 0.969031 9.446898 0.190752 -4.276763\n7456 15.960720 2.405237 1.028400 0.944706 9.529116 0.130120 -4.238812\n7457 15.966737 2.313049 1.059685 0.905424 9.794436 0.150434 -4.282079\n7458 15.972681 2.250647 1.079157 0.886135 9.875520 0.209639 -4.351061\n7459 15.978735 2.115005 1.124788 0.839847 9.850806 0.324734 -4.534935\n7460 15.984670 2.049516 1.151406 0.814681 9.832402 0.406764 -4.620366\n7461 15.990763 1.935254 1.208223 0.756801 9.584613 0.591667 -4.726018\n7462 15.996723 1.885596 1.239227 0.723437 9.404675 0.595390 -4.699175\n7463 16.002678 1.800737 1.309239 0.646772 9.226153 0.265471 -4.478598\n7464 16.008954 1.768113 1.351407 0.607112 9.256560 0.033570 -4.316138\n7465 16.014932 1.722631 1.453740 0.534043 9.414194 -0.249284 -4.044143\n7466 16.020946 1.709721 1.512232 0.503815 9.466908 -0.292131 -3.988107\n7467 16.027033 1.716535 1.630432 0.458257 9.486410 -0.396749 -3.930283\n7468 16.033195 1.726145 1.691463 0.441002 9.512712 -0.521310 -3.900180\n7469 16.039023 1.753880 1.815286 0.410485 9.632488 -0.747795 -3.728762\n7470 16.045095 1.772084 1.875534 0.397052 9.674353 -0.804370 -3.590613\n7471 16.051123 1.796102 1.997529 0.376586 9.713749 -0.966107 -3.306028\n7472 16.057246 1.798223 2.059393 0.371785 9.684757 -1.093776 -3.150425\n7473 16.063268 1.788350 2.182480 0.374270 9.654129 -1.336332 -2.872064\n7474 16.069243 1.784706 2.244004 0.378304 9.711428 -1.337848 -2.707923\n7475 16.075239 1.787003 2.359643 0.386734 9.756566 -1.140386 -2.472548\n7476 16.081446 1.788057 2.411504 0.391372 9.843652 -1.041850 -2.436923\n7477 16.087350 1.781076 2.492722 0.395287 10.257171 -0.887577 -2.503838\n7478 16.093435 1.771348 2.521859 0.395393 10.469947 -0.748869 -2.551475\n7479 16.099502 1.755680 2.558831 0.396766 10.684600 -0.401150 -2.476200\n7480 16.105568 1.752779 2.569350 0.397252 10.611556 -0.292460 -2.355158\n7481 16.111462 1.770220 2.587809 0.397324 10.225616 -0.309210 -1.960490\n7482 16.117404 1.789030 2.596793 0.395515 10.035319 -0.438440 -1.726304\n7483 16.123625 1.832820 2.616972 0.387375 9.757915 -0.741041 -1.243147\n7484 16.129638 1.853885 2.626926 0.383866 9.658017 -0.822225 -1.014531\n7485 16.135747 1.893415 2.636752 0.386117 9.532559 -0.812542 -0.603751\n7486 16.141786 1.916933 2.632577 0.391677 9.531703 -0.752334 -0.371311\n7487 16.147751 1.972252 2.592474 0.407187 9.733338 -0.712537 0.056011\n7488 16.153737 2.002723 2.552316 0.415388 9.909670 -0.720310 0.159201\n7489 16.159881 2.067445 2.436256 0.432357 10.213046 -0.746171 0.271862\n7490 16.165882 2.097424 2.368296 0.440369 10.303253 -0.790709 0.336688\n7491 16.172033 2.145568 2.234626 0.449394 10.382045 -0.891847 0.437774\n7492 16.178059 2.164375 2.177253 0.449191 10.361796 -0.900947 0.465268\n7493 16.184185 2.201433 2.095083 0.435348 10.276043 -0.867293 0.523653\n7494 16.190148 2.222437 2.073317 0.420194 10.233727 -0.937732 0.568159\n7495 16.196120 2.266057 2.067668 0.371080 10.189907 -1.317660 0.713640\n7496 16.202229 2.289991 2.082178 0.337714 10.174931 -1.556703 0.760590\n7497 16.208263 2.340331 2.145367 0.267222 10.089991 -1.933629 0.910775\n7498 16.214229 2.363518 2.193008 0.236556 9.989240 -2.011317 0.965975\n7499 16.220303 2.406213 2.312763 0.189044 9.721115 -1.969349 0.977126\n7500 16.226941 2.429859 2.380658 0.170327 9.580215 -1.993440 1.010182\n7501 16.232548 2.487182 2.520489 0.138625 9.348327 -2.197931 1.246953\n7502 16.239051 2.565046 2.671662 0.115757 9.079115 -2.191375 1.577826\n7503 16.244538 2.599321 2.731486 0.113805 9.035639 -2.043185 1.776764\n7504 16.250995 2.659837 2.831856 0.128461 9.113317 -1.637565 2.195640\n7505 16.256500 2.681757 2.869357 0.142947 9.207441 -1.435657 2.428649\n7506 16.263044 2.707405 2.914861 0.174488 9.411444 -1.133866 2.943698\n7507 16.268657 2.713960 2.925758 0.185579 9.492026 -1.055035 3.236764\n7508 16.275110 2.715344 2.931279 0.192841 9.514950 -0.960026 3.745851\n7509 16.280860 2.708426 2.931010 0.190511 9.475009 -0.959435 3.883657\n7510 16.287149 2.669621 2.932079 0.177747 9.451868 -1.063601 3.985188\n7511 16.292925 2.636942 2.933077 0.168335 9.458390 -1.073218 4.012648\n7512 16.299400 2.551190 2.935637 0.138057 9.394857 -0.998904 4.141026\n7513 16.305012 2.501979 2.935174 0.111788 9.284529 -0.986780 4.263262\n7514 16.311336 2.401239 2.927608 0.027466 8.918406 -1.120723 4.448614\n7515 16.316929 2.347762 2.923187 -0.031667 8.746199 -1.182884 4.514438\n7516 16.323350 2.237620 2.917349 -0.178348 8.514933 -1.175396 4.607256\n7517 16.329005 2.183530 2.918213 -0.261493 8.415177 -1.094224 4.585101\n7518 16.335320 2.078680 2.929506 -0.443091 8.057513 -0.872538 4.517566\n7519 16.341182 2.030511 2.935591 -0.543512 7.767395 -0.722105 4.513636\n7520 16.347371 1.947498 2.943953 -0.769515 7.160971 -0.397611 4.572032\n7521 16.353194 1.920415 2.942527 -0.895888 6.921732 -0.314216 4.764017\n7522 16.359332 1.881116 2.926822 -1.166518 6.685050 -0.227334 5.424452\n7523 16.365469 1.861272 2.914440 -1.305595 6.690696 -0.164390 5.721750\n7524 16.371544 1.809625 2.878257 -1.579679 6.838393 -0.128480 6.096582\n7525 16.377582 1.767151 2.852556 -1.712093 6.956669 -0.303484 6.151665\n7526 16.383593 1.663092 2.776094 -1.975791 7.422362 -0.797617 6.380437\n7527 16.389557 1.601101 2.728374 -2.111166 7.741881 -0.990291 6.564395\n7528 16.395556 1.488955 2.620670 -2.388190 8.191215 -0.989920 6.949599\n7529 16.401721 1.428415 2.566654 -2.527524 8.272164 -0.778056 6.932147\n7530 16.407687 1.287885 2.469590 -2.799798 8.124129 -0.111769 6.600648\n7531 16.413680 1.196867 2.429993 -2.926312 7.927273 0.183899 6.412886\n7532 16.419710 0.984424 2.375088 -3.156034 7.429209 0.651794 6.340616\n7533 16.425804 0.876899 2.360005 -3.259624 7.079313 0.898846 6.395739\n7534 16.432205 0.675317 2.357560 -3.433714 6.353806 1.338809 6.398781\n7535 16.437839 0.577275 2.366387 -3.499304 6.080768 1.461365 6.317434\n7536 16.443899 0.380968 2.397895 -3.585594 5.782125 1.655370 6.209602\n7537 16.449931 0.283677 2.419794 -3.610293 5.764473 1.737964 6.323816\n7538 16.456349 0.094445 2.473142 -3.637324 5.923210 1.720814 6.693687\n7539 16.462088 -0.002008 2.503667 -3.645321 6.061110 1.676515 6.782456\n7540 16.468185 -0.172464 2.561481 -3.656204 6.189230 1.926515 6.772620\n7541 16.474090 -0.240753 2.588927 -3.659115 6.085777 2.208531 6.737755\n7542 16.480185 -0.329298 2.643284 -3.661921 5.503110 2.707502 6.726338\n7543 16.486112 -0.357783 2.667793 -3.662930 5.125141 2.837646 6.732264\n7544 16.492200 -0.386941 2.706934 -3.668751 4.523816 2.935802 6.794960\n7545 16.498341 -0.393961 2.722920 -3.673690 4.409587 2.993695 7.008808\n7546 16.504346 -0.393779 2.747122 -3.680935 4.440083 3.020066 7.558154\n7547 16.510454 -0.392503 2.757888 -3.678061 4.455994 3.027257 7.710105\n7548 16.516364 -0.396636 2.765860 -3.651315 4.516681 3.138711 7.714371\n7549 16.522593 -0.402763 2.761491 -3.627718 4.504388 3.178098 7.628052\n7550 16.528436 -0.420978 2.745639 -3.571010 4.280911 3.150625 7.686561\n7551 16.534555 -0.436912 2.735220 -3.543238 4.085116 3.171684 7.796360\n7552 16.540561 -0.497686 2.718723 -3.490469 3.628112 3.482381 7.812721\n7553 16.546420 -0.545983 2.713956 -3.462773 3.441315 3.662480 7.800551\n7554 16.552731 -0.688829 2.713442 -3.397642 2.994064 3.877492 7.628702\n7555 16.558704 -0.774078 2.719086 -3.361475 2.813183 3.957284 7.628463\n7556 16.564966 -0.950227 2.738815 -3.288570 2.430681 4.203083 7.775159\n7557 16.570750 -1.036057 2.752217 -3.256214 2.309455 4.302969 7.839438\n7558 16.576953 -1.187658 2.774681 -3.208522 2.123116 4.493649 7.898435\n7559 16.582843 -1.249926 2.783195 -3.192187 1.991202 4.636933 7.852074\n7560 16.589077 -1.333168 2.796996 -3.164638 1.717303 5.081941 7.822674\n7561 16.594929 -1.357749 2.799488 -3.149597 1.625936 5.252604 7.874695\n7562 16.600984 -1.361453 2.793382 -3.114702 1.588308 5.163676 8.030490\n7563 16.607005 -1.339529 2.782529 -3.098592 1.602550 5.002185 8.093041\n7564 16.613013 -1.265296 2.738263 -3.075014 1.718158 4.786465 8.091115\n7565 16.619091 -1.220999 2.705212 -3.066458 1.828583 4.725412 8.062969\n7566 16.625071 -1.143470 2.624291 -3.054707 1.875781 4.535870 7.947475\n7567 16.631730 -1.104502 2.526340 -3.068429 1.131040 4.065028 7.894627\n7568 16.637327 -1.101077 2.486695 -3.091941 0.636508 3.908954 8.067644\n7569 16.643728 -1.110770 2.428458 -3.170968 -0.221794 3.706857 8.693176\n7570 16.649357 -1.128388 2.410190 -3.222979 -0.487887 3.483697 8.969584\n7571 16.655820 -1.205438 2.381747 -3.341867 -0.713401 2.723586 9.324234\n7572 16.661405 -1.265965 2.366712 -3.400513 -0.708422 2.333514 9.494631\n7573 16.667766 -1.411501 2.333352 -3.490120 -0.645069 1.900363 9.881205\n7574 16.673557 -1.491444 2.312419 -3.513951 -0.607308 1.897975 10.053032\n7575 16.679921 -1.652129 2.257465 -3.515957 -0.762168 2.203237 10.092613\n7576 16.685554 -1.726075 2.225991 -3.496880 -0.986128 2.411871 9.985091\n7577 16.691857 -1.863561 2.165647 -3.431138 -1.554161 2.878487 9.749891\n7578 16.697990 -1.932966 2.139322 -3.389861 -1.725110 3.135350 9.589449\n7579 16.703853 -2.065340 2.096339 -3.290429 -1.844688 3.457700 9.106508\n7580 16.709842 -2.124616 2.078123 -3.233448 -1.810819 3.423142 8.911074\n7581 16.716059 -2.218545 2.049115 -3.110992 -1.854591 3.160193 8.793544\n7582 16.721935 -2.250541 2.043544 -3.041887 -1.995505 3.107626 8.815065\n7583 16.728097 -2.281930 2.059317 -2.885221 -2.309289 3.368638 8.763248\n7584 16.733944 -2.285919 2.080366 -2.799191 -2.561405 3.556010 8.623662\n7585 16.739983 -2.288051 2.145860 -2.614971 -3.197366 3.757368 8.285262\n7586 16.746096 -2.289174 2.186873 -2.521765 -3.361373 3.808168 8.170444\n7587 16.752067 -2.273841 2.281055 -2.329646 -3.409261 3.953485 8.213602\n7588 16.758116 -2.255888 2.333501 -2.225975 -3.334013 3.928519 8.259646\n7589 16.764220 -2.218562 2.439728 -2.007355 -3.178593 3.597014 8.207662\n7590 16.770137 -2.209196 2.489265 -1.894225 -3.199315 3.363255 8.179878\n7591 16.776152 -2.230065 2.580017 -1.669397 -3.301031 2.564383 8.108634\n7592 16.782162 -2.264191 2.619057 -1.565932 -3.454101 1.999131 8.117026\n7593 16.788403 -2.372770 2.681904 -1.384574 -4.007101 0.954875 8.297704\n7594 16.794442 -2.444029 2.709870 -1.306342 -4.214969 0.679554 8.495663\n7595 16.800416 -2.587541 2.758388 -1.161397 -4.333745 0.380337 8.848121\n7596 16.806538 -2.656757 2.779278 -1.088918 -4.173421 0.206139 8.868344\n7597 16.812410 -2.792989 2.796463 -0.947134 -3.494786 -0.274751 8.790083\n7598 16.818679 -2.856694 2.789783 -0.884897 -3.124862 -0.601856 8.631131\n7599 16.824541 -2.952024 2.748280 -0.783735 -2.874389 -1.306692 8.655046\n7600 16.830678 -2.979926 2.713722 -0.748301 -2.912912 -1.539920 8.641020\n7601 16.836686 -2.994947 2.627825 -0.699038 -3.456984 -1.727821 8.602740\n7602 16.842686 -2.980431 2.577502 -0.677771 -3.933522 -1.867108 8.633820\n7603 16.848686 -2.919958 2.472322 -0.649585 -4.841647 -2.376552 8.658895\n7604 16.854637 -2.880670 2.414170 -0.649071 -5.155143 -2.575667 8.598761\n7605 16.860793 -2.792899 2.277064 -0.669858 -5.347761 -2.858190 8.426670\n7606 16.866820 -2.742067 2.199187 -0.691574 -5.334080 -2.997297 8.430158\n7607 16.872912 -2.625954 2.027097 -0.749513 -5.424815 -3.092878 8.470419\n7608 16.878893 -2.558262 1.933291 -0.775272 -5.540862 -3.061766 8.328759\n7609 16.884943 -2.415528 1.739131 -0.808901 -5.829828 -3.134503 7.955039\n7610 16.890851 -2.344577 1.641482 -0.821115 -5.981918 -3.239994 7.786372\n7611 16.897065 -2.199763 1.449794 -0.850889 -6.072638 -3.478684 7.580533\n7612 16.903006 -2.122754 1.358683 -0.873874 -5.941827 -3.611651 7.505722\n7613 16.909042 -1.967699 1.189803 -0.941928 -5.465627 -3.767621 7.406904\n7614 16.915031 -1.888887 1.116733 -0.979600 -5.354785 -3.776621 7.411961\n7615 16.921162 -1.729153 1.015165 -1.047855 -5.489357 -3.877017 7.333382\n7616 16.927241 -1.654805 0.989269 -1.079542 -5.633593 -3.993333 7.215792\n7617 16.933172 -1.528112 0.977577 -1.134787 -6.064068 -4.388457 6.978194\n7618 16.939362 -1.472227 0.989641 -1.161019 -6.254165 -4.513936 6.892575\n7619 16.945357 -1.377499 1.035560 -1.221773 -6.245955 -4.309193 6.604384\n7620 16.951382 -1.344948 1.061246 -1.250434 -6.037072 -4.033559 6.389507\n7621 16.957348 -1.296680 1.119137 -1.283834 -5.866140 -3.798305 6.317853\n7622 16.963560 -1.270675 1.158486 -1.295212 -5.829862 -3.842724 6.376604\n7623 16.969544 -1.230008 1.259614 -1.315170 -5.831789 -3.808413 6.123979\n7624 16.975513 -1.219477 1.314785 -1.319112 -5.795062 -3.822087 5.870427\n7625 16.981552 -1.219680 1.425483 -1.328022 -5.507222 -3.958716 5.687870\n7626 16.987659 -1.223409 1.473171 -1.334876 -5.503591 -3.992896 5.789228\n7627 16.993764 -1.217120 1.552021 -1.328505 -5.847090 -3.993413 5.966049\n7628 16.999740 -1.210541 1.586164 -1.318628 -5.855536 -4.006010 5.816629\n7629 17.005694 -1.221437 1.636935 -1.281030 -5.711409 -4.086225 5.476497\n7630 17.011672 -1.240355 1.653241 -1.250762 -5.533116 -4.207340 5.394026\n7631 17.018167 -1.283991 1.683577 -1.194588 -5.182590 -4.688948 5.565819\n7632 17.024390 -1.304363 1.695117 -1.170471 -5.231717 -4.918995 5.555453\n7633 17.030140 -1.324929 1.707329 -1.101725 -5.591409 -5.235998 5.243890\n7634 17.036485 -1.352816 1.729795 -1.018794 -6.306267 -5.593415 5.549833\n7635 17.041959 -1.349032 1.746307 -0.978193 -6.742853 -5.778115 5.604952\n7636 17.048558 -1.296484 1.781850 -0.905061 -7.371025 -6.454217 5.645752\n7637 17.054164 -1.277761 1.781554 -0.888843 -7.468089 -6.698166 5.699987\n7638 17.060417 -1.206339 1.746384 -0.856437 -7.504339 -7.027702 5.699372\n7639 17.066191 -1.148022 1.708274 -0.843348 -7.324368 -7.056207 5.769179\n7640 17.072591 -0.987450 1.546751 -0.830221 -6.323969 -7.240603 5.702170\n7641 17.078309 -0.904895 1.445743 -0.833783 -5.698023 -7.397936 5.652303\n7642 17.084624 -0.734895 1.206403 -0.870640 -4.496551 -7.862929 5.793313\n7643 17.090368 -0.657997 1.078012 -0.907191 -4.187991 -8.140991 5.784696\n7644 17.096861 -0.530486 0.840102 -1.006612 -4.449660 -8.761020 5.529698\n7645 17.102605 -0.482914 0.740692 -1.063563 -4.994991 -9.075054 5.331910\n7646 17.109925 -0.405488 0.602686 -1.180480 -6.527584 -9.638660 4.937035\n7647 17.114566 -0.363943 0.565812 -1.237071 -7.257068 -9.890202 4.795582\n7648 17.120576 -0.270533 0.536202 -1.342675 -8.222174 -10.224988 4.528202\n7649 17.126447 -0.211111 0.534403 -1.384776 -8.606230 -10.303226 4.506470\n7650 17.132773 -0.058912 0.554365 -1.435046 -9.093542 -10.153098 4.288958\n7651 17.138641 0.028106 0.572271 -1.441019 -9.152531 -9.989826 4.078343\n7652 17.144775 0.213530 0.602374 -1.409246 -8.684468 -9.614756 3.652033\n7653 17.150615 0.314280 0.611375 -1.374983 -8.225505 -9.398123 3.682725\n7654 17.156907 0.526805 0.602641 -1.287043 -7.300372 -9.082418 4.152308\n7655 17.162939 0.623471 0.580094 -1.237728 -6.954239 -9.060932 4.379321\n7656 17.168889 0.770887 0.493614 -1.135009 -6.540677 -9.164162 4.688279\n7657 17.174895 0.814248 0.431932 -1.083346 -6.500176 -9.229261 4.846476\n7658 17.180974 0.844303 0.282608 -0.976175 -6.534966 -9.284424 5.118985\n7659 17.186904 0.842693 0.199715 -0.920739 -6.545576 -9.262498 5.172327\n7660 17.193039 0.837389 0.025726 -0.810190 -6.443066 -9.355017 5.055093\n7661 17.198961 0.844394 -0.063944 -0.758068 -6.338322 -9.519049 4.943445\n7662 17.205062 0.899701 -0.240165 -0.668718 -6.220205 -9.859566 4.824017\n7663 17.211179 0.950683 -0.323384 -0.632728 -6.242182 -9.947013 4.838774\n7664 17.217135 1.090245 -0.478123 -0.575945 -6.412690 -10.007718 4.914298\n7665 17.223270 1.173833 -0.551800 -0.552114 -6.524756 -10.066997 4.980964\n7666 17.229423 1.364183 -0.701706 -0.514990 -6.786067 -10.365760 5.189097\n7667 17.235383 1.474190 -0.783191 -0.504819 -6.945863 -10.578899 5.344423\n7668 17.241201 1.722134 -0.969126 -0.506657 -7.293404 -10.975399 5.665839\n7669 17.247387 1.857532 -1.074196 -0.517261 -7.565793 -11.054057 5.751204\n7670 17.253341 2.145234 -1.308515 -0.543048 -8.455586 -10.804050 5.827525\n7671 17.259460 2.293973 -1.435438 -0.553395 -9.040575 -10.515006 5.861785\n7672 17.265638 2.600724 -1.709176 -0.562574 -10.233590 -9.762448 5.967260\n7673 17.271437 2.758803 -1.856567 -0.562208 -10.672969 -9.373100 6.006177\n7674 17.277697 3.081955 -2.176750 -0.559457 -10.881653 -8.622807 6.031935\n7675 17.283676 3.244144 -2.350391 -0.557722 -10.537145 -8.241175 6.014675\n7676 17.289799 3.550731 -2.717436 -0.548629 -8.895457 -7.512911 5.962611\n7677 17.295800 3.684820 -2.906338 -0.540855 -7.751616 -7.198403 5.960879\n7678 17.301828 3.894068 -3.278220 -0.525732 -5.457779 -6.701100 6.072414\n7679 17.307713 3.963768 -3.451045 -0.524912 -4.542119 -6.517941 6.204601\n7680 17.313834 4.033884 -3.748389 -0.557351 -3.437500 -6.246628 6.491272\n7681 17.319807 4.035408 -3.867118 -0.594678 -3.195170 -6.145291 6.584286\n7682 17.325987 3.985640 -4.038137 -0.708890 -3.060544 -6.061195 6.584249\n7683 17.332087 3.940211 -4.089054 -0.780231 -3.069348 -6.072671 6.529320\n7684 17.338042 3.816976 -4.125169 -0.934983 -3.197634 -6.031181 6.431887\n7685 17.344004 3.750058 -4.112194 -1.013523 -3.339033 -5.953139 6.399715\n7686 17.349950 3.633467 -4.027015 -1.165740 -3.728590 -5.753638 6.428208\n7687 17.356120 3.588020 -3.957073 -1.237988 -3.972816 -5.661031 6.499054\n7688 17.362415 3.542998 -3.760104 -1.367643 -4.602077 -5.505237 6.733030\n7689 17.368177 3.542990 -3.633191 -1.425167 -4.931308 -5.349059 6.720673\n7690 17.374163 3.577671 -3.352251 -1.511836 -5.382034 -4.973271 6.628443\n7691 17.380287 3.606278 -3.208077 -1.538468 -5.365406 -4.759253 6.640690\n7692 17.386244 3.686280 -2.942803 -1.569646 -4.852419 -4.219700 7.293309\n7693 17.392287 3.729270 -2.834767 -1.579993 -4.464034 -3.966286 7.739826\n7694 17.398521 3.817455 -2.686039 -1.600836 -3.596467 -3.480484 8.313327\n7695 17.404395 3.852952 -2.650099 -1.612105 -3.164987 -3.235948 8.378760\n7696 17.410741 3.884326 -2.654051 -1.632613 -2.356961 -2.704236 8.207220\n7697 17.416587 3.885951 -2.686281 -1.639426 -1.975655 -2.438838 8.130233\n7698 17.422466 3.882125 -2.795671 -1.650274 -1.155307 -2.109958 8.125312\n7699 17.429178 3.871971 -2.947996 -1.665166 -0.333546 -2.027632 8.012015\n7700 17.434676 3.862203 -3.032310 -1.675301 0.003819 -1.979281 7.911158\n7701 17.440637 3.846758 -3.117473 -1.688074 0.247698 -1.872993 7.866785\n7702 17.446794 3.797247 -3.269987 -1.720887 0.374726 -1.469150 8.076053\n7703 17.453290 3.721004 -3.377928 -1.764274 0.170861 -1.161874 8.464810\n7704 17.458895 3.671497 -3.414810 -1.793212 0.023540 -1.050596 8.633556\n7705 17.465390 3.564190 -3.460849 -1.869470 -0.237039 -0.709003 8.912321\n7706 17.470923 3.511194 -3.470984 -1.914854 -0.315352 -0.523742 9.075294\n7707 17.477509 3.409176 -3.467496 -2.009189 -0.227575 -0.322883 9.298214\n7708 17.483017 3.362558 -3.454014 -2.052768 -0.019955 -0.292883 9.256722\n7709 17.489419 3.275523 -3.412299 -2.115452 0.810791 -0.412590 8.836408\n7710 17.495254 3.234327 -3.390762 -2.128721 1.326527 -0.509529 8.625097\n7711 17.501537 3.164834 -3.357760 -2.110402 2.049593 -0.461170 8.725380\n7712 17.507160 3.136733 -3.348305 -2.082444 2.109946 -0.170783 8.822851\n7713 17.513400 3.097744 -3.349352 -2.005228 1.765055 0.617831 8.840405\n7714 17.519303 3.076597 -3.359422 -1.963180 1.536145 0.905447 8.704249\n7715 17.525553 3.024066 -3.393393 -1.892094 1.291713 1.269257 8.490546\n7716 17.531543 2.990142 -3.414212 -1.866257 1.229721 1.487011 8.376136\n7717 17.537645 2.918415 -3.458487 -1.834874 1.197978 2.039976 8.179799\n7718 17.543293 2.886797 -3.485133 -1.830249 1.229460 2.304639 8.154597\n7719 17.549651 2.817421 -3.540295 -1.844746 1.132268 2.668051 8.158884\n7720 17.555408 2.782733 -3.569830 -1.867272 1.069316 2.683450 8.240111\n7721 17.561726 2.697247 -3.631565 -1.942230 1.051229 2.424838 8.306396\n7722 17.567563 2.646163 -3.657971 -1.986683 1.170362 2.308906 8.281460\n7723 17.573636 2.534491 -3.701200 -2.064657 1.817356 2.325515 7.989036\n7724 17.579657 2.482795 -3.719786 -2.090384 2.251594 2.428095 7.791282\n7725 17.585810 2.391933 -3.748988 -2.108916 3.114025 2.709976 7.333322\n7726 17.591744 2.362968 -3.765331 -2.107106 3.482404 2.812618 7.222182\n7727 17.597945 2.328191 -3.804578 -2.090662 3.802260 2.989968 6.854505\n7728 17.603695 2.313820 -3.821147 -2.078618 3.864813 3.204975 6.672412\n7729 17.609812 2.294149 -3.850159 -2.046442 3.865205 3.894937 6.354394\n7730 17.615829 2.281181 -3.854744 -2.023474 3.940746 4.294927 6.110567\n7731 17.621914 2.274636 -3.849087 -1.968558 4.272525 5.029219 5.872882\n7732 17.628037 2.272438 -3.843199 -1.942409 4.437815 5.290470 5.656080\n7733 17.634032 2.274139 -3.826111 -1.910919 4.677248 5.589468 5.544745\n7734 17.639994 2.272857 -3.816835 -1.908573 4.661029 5.648554 5.522027\n7735 17.646102 2.227516 -3.780779 -1.925015 4.551292 5.818407 5.192243\n7736 17.652362 2.184756 -3.757865 -1.937659 4.467919 5.930342 5.049176\n7737 17.658144 2.066629 -3.698155 -1.957697 4.014855 6.087211 4.811450\n7738 17.664291 1.997665 -3.656984 -1.968177 3.781327 6.140738 4.854709\n7739 17.670339 1.857760 -3.569369 -1.999212 3.556998 6.076499 4.916279\n7740 17.676339 1.788561 -3.524305 -2.017237 3.587546 5.970633 4.767374\n7741 17.682475 1.647032 -3.440599 -2.052042 4.073538 5.979172 4.509175\n7742 17.688568 1.576112 -3.407070 -2.063594 4.455955 6.143295 4.359427\n7743 17.694695 1.466991 -3.350967 -2.055479 5.068177 6.498972 4.192325\n7744 17.700525 1.421270 -3.328178 -2.039548 5.377999 6.564245 4.044627\n7745 17.706628 1.387567 -3.305595 -1.995721 5.666146 6.574435 3.933902\n7746 17.712698 1.376568 -3.296098 -1.968103 5.683305 6.617393 3.675553\n7747 17.718675 1.395084 -3.275415 -1.908998 5.321385 7.025255 3.563272\n7748 17.724613 1.394236 -3.261424 -1.876693 5.046531 7.307953 3.390151\n7749 17.730747 1.399355 -3.222164 -1.811697 4.755554 7.809535 3.139848\n7750 17.736729 1.385968 -3.201907 -1.783734 4.672989 8.010173 3.108043\n7751 17.742708 1.336599 -3.163705 -1.748162 4.654804 8.275937 3.020275\n7752 17.748936 1.303712 -3.142660 -1.739840 4.660179 8.284354 2.955264\n7753 17.754934 1.226505 -3.097976 -1.732387 4.604370 8.136500 2.873237\n7754 17.761056 1.184946 -3.072587 -1.728794 4.616116 8.024051 2.799057\n7755 17.767062 1.106228 -3.014707 -1.710761 4.737444 7.826430 2.646528\n7756 17.773177 1.072198 -2.986785 -1.693881 4.790438 7.707058 2.528898\n7757 17.778952 1.022812 -2.936195 -1.652083 4.882785 7.390925 2.409886\n7758 17.785085 1.009938 -2.911928 -1.631176 4.964914 7.181540 2.394419\n7759 17.791103 1.002334 -2.858519 -1.590422 5.366351 6.780173 2.229936\n7760 17.797210 1.007923 -2.827575 -1.569774 5.705515 6.667373 2.005347\n7761 17.803262 1.034708 -2.753298 -1.524594 6.417922 6.683604 1.530350\n7762 17.809182 1.054810 -2.708775 -1.501447 6.709822 6.756325 1.330154\n7763 17.815386 1.102431 -2.596931 -1.469159 6.972091 7.056956 1.051133\n7764 17.821311 1.128741 -2.527811 -1.462503 6.866114 7.300959 1.013586\n7765 17.827477 1.198390 -2.360268 -1.464217 6.287031 7.781718 0.786593\n7766 17.833402 1.245348 -2.263314 -1.468609 5.867702 7.982661 0.682735\n7767 17.839480 1.325185 -2.064695 -1.476114 5.094106 8.204556 0.360304\n7768 17.845421 1.356208 -1.971932 -1.478728 4.856337 8.238618 0.080529\n7769 17.851682 1.394524 -1.804034 -1.484635 4.719466 8.543832 -0.162109\n7770 17.858074 1.390842 -1.751837 -1.490670 4.772143 8.798584 -0.088314\n7771 17.863542 1.354119 -1.673909 -1.511523 4.729256 9.164017 0.203458\n7772 17.870066 1.319830 -1.640546 -1.524572 4.595992 9.178461 0.300892\n7773 17.875819 1.223121 -1.568471 -1.545814 4.391912 8.983388 0.059395\n7774 17.882307 1.101751 -1.473409 -1.536213 4.516650 8.736690 -0.249208\n7775 17.887924 1.040118 -1.416630 -1.515839 4.681257 8.638863 -0.294063\n7776 17.894518 0.935551 -1.289735 -1.454294 4.898123 8.469838 -0.159082\n7777 17.900056 0.895605 -1.223404 -1.415463 4.892769 8.378396 -0.036631\n7778 17.906453 0.827297 -1.093739 -1.325873 4.910550 8.286887 0.011640\n7779 17.912083 0.791036 -1.032168 -1.276963 4.973517 8.332492 -0.058911\n7780 17.918366 0.697923 -0.919589 -1.167666 5.107543 8.485490 -0.177576\n7781 17.924100 0.638963 -0.866906 -1.108829 5.161458 8.525097 -0.202729\n7782 17.930231 0.503536 -0.762212 -0.995955 5.259385 8.583627 -0.276311\n7783 17.936163 0.429021 -0.707154 -0.944393 5.344088 8.660037 -0.374132\n7784 17.942253 0.272512 -0.579424 -0.855773 5.517910 8.925457 -0.691651\n7785 17.948336 0.189764 -0.501184 -0.820089 5.539687 9.068338 -0.915650\n7786 17.954429 0.011125 -0.311246 -0.763361 5.418884 9.340693 -1.468843\n7787 17.960591 -0.086968 -0.199110 -0.741526 5.290531 9.442448 -1.769053\n7788 17.966494 -0.291823 0.059609 -0.712622 4.749424 9.486039 -2.035280\n7789 17.972406 -0.391435 0.206249 -0.705463 4.360698 9.425451 -1.995082\n7790 17.978530 -0.576696 0.536255 -0.706528 3.721899 9.344971 -1.836102\n7791 17.984439 -0.661730 0.714101 -0.712435 3.545547 9.350282 -1.782322\n7792 17.990551 -0.823382 1.079420 -0.726027 3.481852 9.424411 -1.757919\n7793 17.996584 -0.899470 1.261524 -0.734345 3.518059 9.473200 -1.676203\n7794 18.002731 -1.040341 1.609984 -0.756472 3.514490 9.522605 -1.346053\n7795 18.008624 -1.102675 1.773451 -0.770371 3.476034 9.496691 -1.181430\n7796 18.014762 -1.208950 2.068643 -0.804930 3.435792 9.491968 -0.929863\n7797 18.020754 -1.253698 2.196269 -0.822705 3.462587 9.552759 -0.854488\n7798 18.026905 -1.334157 2.411191 -0.851876 3.662591 9.673994 -0.623312\n7799 18.032856 -1.375669 2.500100 -0.863780 3.793772 9.644138 -0.447881\n7800 18.038809 -1.468407 2.645291 -0.886953 4.004332 9.390585 -0.171877\n7801 18.044970 -1.522512 2.702456 -0.897297 4.025358 9.238835 -0.099421\n7802 18.050924 -1.645899 2.790920 -0.912012 3.807470 9.060404 0.081483\n7803 18.057017 -1.705815 2.825802 -0.915799 3.653846 9.089806 0.223872\n7804 18.063042 -1.803083 2.887912 -0.914772 3.224390 9.373431 0.537203\n7805 18.069047 -1.840420 2.917844 -0.911718 3.003160 9.514071 0.674206\n7806 18.075066 -1.897499 2.981121 -0.909173 2.707685 9.663157 0.910076\n7807 18.081113 -1.917519 3.014740 -0.909369 2.618407 9.683354 1.042782\n7808 18.087167 -1.940641 3.083032 -0.907198 2.562986 9.633694 1.368790\n7809 18.093259 -1.940573 3.117813 -0.903692 2.572915 9.567294 1.543344\n7810 18.099332 -1.910569 3.187286 -0.884803 2.667599 9.378722 1.944452\n7811 18.105262 -1.881866 3.220518 -0.866792 2.763691 9.282900 2.088383\n7812 18.111330 -1.803918 3.283028 -0.816276 2.872663 9.246551 2.299435\n7813 18.117315 -1.761881 3.311938 -0.784916 2.828921 9.264506 2.400527\n7814 18.123462 -1.688662 3.368771 -0.715048 2.637147 9.169657 2.652381\n7815 18.129435 -1.663929 3.397917 -0.677909 2.528538 9.077116 2.818791\n7816 18.135417 -1.638311 3.454517 -0.596227 2.244382 9.057875 2.998301\n7817 18.141540 -1.635695 3.482122 -0.550664 2.062966 9.166475 3.059148\n7818 18.147657 -1.645503 3.532148 -0.454338 1.676889 9.381855 3.067917\n7819 18.153640 -1.655586 3.555212 -0.406195 1.553545 9.430706 2.987427\n7820 18.158837 -1.689355 3.586788 -0.320169 1.540318 9.524805 2.738950\n7821 18.164561 -1.708017 3.593130 -0.285349 1.559723 9.634407 2.595602\n7822 18.170920 -1.737947 3.593148 -0.232981 1.495407 9.958278 2.715415\n7823 18.176865 -1.748877 3.589117 -0.215072 1.422007 10.112793 2.882696\n7824 18.182831 -1.758048 3.580348 -0.190275 1.306211 10.160127 3.338598\n7825 18.188934 -1.757540 3.576243 -0.181285 1.343107 9.994848 3.604610\n7826 18.194978 -1.757943 3.564502 -0.164082 1.557603 9.384046 4.048138\n7827 18.200968 -1.758640 3.556864 -0.152201 1.634585 9.037068 4.189994\n7828 18.206945 -1.776291 3.534099 -0.113680 1.661095 8.480007 4.480399\n7829 18.212986 -1.791304 3.517368 -0.086308 1.554115 8.256008 4.481837\n7830 18.219254 -1.829778 3.480779 -0.013602 1.124683 7.935345 4.550035\n7831 18.225037 -1.864233 3.459447 0.030890 0.906551 7.791093 4.643894\n7832 18.231305 -1.946908 3.418466 0.128765 0.420878 7.514369 4.536997\n7833 18.237023 -1.998099 3.400170 0.179773 0.201792 7.459819 4.662835\n7834 18.243142 -2.133281 3.362488 0.278766 -0.080390 7.452066 5.095829\n7835 18.249128 -2.215590 3.351044 0.338921 -0.224985 7.454479 5.272375\n7836 18.255320 -2.351876 3.350196 0.432889 -0.493028 7.413949 5.880647\n7837 18.261668 -2.429971 3.354926 0.476467 -0.599242 7.339863 6.056850\n7838 18.267458 -2.559694 3.388930 0.555622 -0.801101 7.133916 6.174443\n7839 18.273542 -2.615819 3.411829 0.594073 -0.876726 6.983528 6.273201\n7840 18.279583 -2.735928 3.460455 0.672079 -0.958998 6.746485 6.472883\n7841 18.285507 -2.780012 3.491819 0.711594 -0.987684 6.778928 6.520265\n7842 18.291601 -2.826787 3.553439 0.794763 -1.125687 7.185726 6.322567\n7843 18.297535 -2.836621 3.579131 0.835595 -1.297990 7.408454 6.092476\n7844 18.303696 -2.831400 3.628125 0.913297 -1.645960 7.691453 5.984993\n7845 18.309655 -2.809000 3.652473 0.948913 -1.688481 7.750724 5.986039\n7846 18.315818 -2.741759 3.696790 1.020800 -1.597951 7.691462 6.176252\n7847 18.321839 -2.699354 3.716190 1.060655 -1.524432 7.544627 6.246326\n7848 18.327780 -2.610743 3.751304 1.151340 -1.446926 7.146010 6.594247\n7849 18.333787 -2.569826 3.765570 1.200645 -1.421127 6.972404 6.788878\n7850 18.339810 -2.501250 3.786573 1.299062 -1.332077 6.877552 6.927665\n7851 18.345844 -2.472725 3.789309 1.345248 -1.371146 6.883749 6.926224\n7852 18.352122 -2.447426 3.774470 1.426312 -1.656977 6.889334 6.942400\n7853 18.358097 -2.446354 3.756860 1.458661 -1.857468 6.907135 6.962913\n7854 18.364486 -2.469566 3.700922 1.515160 -2.275422 6.925530 7.008996\n7855 18.370016 -2.495998 3.661394 1.542262 -2.430405 6.883638 7.032446\n7856 18.376186 -2.581058 3.561936 1.592711 -2.672466 6.621075 7.118241\n7857 18.382327 -2.636892 3.504797 1.618043 -2.796942 6.421329 7.285486\n7858 18.388162 -2.772045 3.374835 1.666027 -2.942682 6.094899 7.663573\n7859 18.394291 -2.842727 3.304365 1.685846 -3.011650 5.968392 7.747156\n7860 18.400220 -2.983022 3.159011 1.716289 -3.435399 5.781050 7.999079\n7861 18.406409 -3.051308 3.086074 1.724789 -3.646317 5.725272 8.084800\n7862 18.412529 -3.162164 2.949118 1.725384 -3.813764 5.654102 8.074164\n7863 18.418522 -3.203689 2.881944 1.721535 -3.747988 5.598339 8.040009\n7864 18.424428 -3.272846 2.746884 1.706934 -3.528839 5.295351 7.839912\n7865 18.430481 -3.297952 2.682761 1.695369 -3.519197 5.121360 7.764470\n7866 18.436723 -3.332064 2.567514 1.667154 -3.585584 4.848928 7.737213\n7867 18.442765 -3.344948 2.517778 1.653579 -3.610238 4.750121 7.761246\n7868 18.448581 -3.361899 2.434247 1.628423 -3.672244 4.586303 7.794302\n7869 18.454642 -3.368079 2.399088 1.617329 -3.742335 4.499020 7.817331\n7870 18.460769 -3.381474 2.339263 1.604715 -3.994940 4.246842 7.840596\n7871 18.467507 -3.387218 2.292563 1.606737 -4.170121 3.781736 7.909413\n7872 18.472883 -3.386347 2.271813 1.614512 -4.155161 3.533293 7.964770\n7873 18.479210 -3.369022 2.237229 1.645670 -4.088083 3.221406 8.006756\n7874 18.484845 -3.350235 2.225828 1.672199 -4.153746 3.134883 8.005322\n7875 18.491365 -3.310326 2.217424 1.745314 -4.512389 2.976963 8.040014\n7876 18.496924 -3.291617 2.220299 1.789633 -4.710033 2.868879 8.026542\n7877 18.503578 -3.259412 2.234225 1.888495 -4.825714 2.675668 8.055983\n7878 18.509015 -3.245149 2.239828 1.941652 -4.738514 2.632647 8.111893\n7879 18.515498 -3.217749 2.245037 2.050438 -4.566708 2.631774 8.342493\n7880 18.521082 -3.204255 2.245337 2.104642 -4.496090 2.630196 8.444829\n7881 18.527525 -3.181222 2.240501 2.210001 -4.521069 2.661862 8.508823\n7882 18.533278 -3.173965 2.234540 2.261363 -4.603192 2.674994 8.504298\n7883 18.539573 -3.164569 2.213711 2.356164 -4.697618 2.489423 8.432739\n7884 18.545255 -3.155955 2.197173 2.398232 -4.645732 2.262578 8.380087\n7885 18.551528 -3.117712 2.155283 2.468954 -4.322459 1.834028 8.484573\n7886 18.557383 -3.084772 2.135886 2.499296 -4.200492 1.756263 8.614687\n7887 18.563633 -2.987972 2.116955 2.554590 -4.271478 1.863808 8.667938\n7888 18.570063 -2.929945 2.117742 2.580490 -4.491565 1.978978 8.568088\n7889 18.575474 -2.808343 2.130079 2.625419 -5.193021 2.115937 8.249184\n7890 18.581503 -2.742522 2.137167 2.641966 -5.522666 2.153043 8.141242\n7891 18.587527 -2.594116 2.136720 2.663516 -5.842932 2.226575 8.017075\n7892 18.593629 -2.511675 2.123745 2.674475 -5.873787 2.131666 7.970053\n7893 18.599598 -2.329865 2.071023 2.710417 -5.629317 1.709442 7.897794\n7894 18.605664 -2.234636 2.036871 2.737936 -5.543072 1.568646 7.991769\n7895 18.611719 -2.061152 1.970918 2.814246 -5.557897 1.538198 8.521711\n7896 18.617621 -1.982712 1.945304 2.858754 -5.532664 1.488055 8.797654\n7897 18.623866 -1.842462 1.904112 2.947230 -5.458419 1.171304 9.069698\n7898 18.629744 -1.780655 1.881595 2.988606 -5.476319 1.027001 9.026433\n7899 18.635956 -1.655004 1.826295 3.066200 -5.559081 1.038094 8.860093\n7900 18.641844 -1.584621 1.795948 3.108927 -5.580822 1.155470 8.828777\n7901 18.647971 -1.417442 1.724937 3.229268 -5.648924 1.242831 8.640512\n7902 18.653970 -1.345085 1.690562 3.287933 -5.727081 1.070310 8.516672\n7903 18.660035 -1.228441 1.623409 3.394932 -6.102089 0.903035 8.644588\n7904 18.666037 -1.185893 1.591287 3.440132 -6.434754 1.122532 8.781321\n7905 18.672248 -1.117122 1.532830 3.511490 -7.178235 1.795253 8.782228\n7906 18.678069 -1.084139 1.499646 3.538602 -7.426244 1.988337 8.596826\n7907 18.684172 -1.008441 1.412994 3.579870 -7.364813 1.954140 8.288254\n7908 18.690045 -0.961808 1.360875 3.594560 -7.196468 1.923322 8.359141\n7909 18.696218 -0.852319 1.254445 3.614873 -6.981852 2.039337 8.609257\n7910 18.702379 -0.797863 1.204276 3.619926 -6.930996 2.109798 8.629132\n7911 18.708227 -0.711359 1.109686 3.618479 -6.906160 2.242473 8.415805\n7912 18.714490 -0.677234 1.065353 3.613847 -6.917388 2.382548 8.297805\n7913 18.720402 -0.602897 0.984079 3.603955 -6.937189 2.722717 8.229049\n7914 18.726456 -0.556461 0.945825 3.601152 -6.942725 2.810863 8.184998\n7915 18.732538 -0.443525 0.870095 3.596215 -6.858982 2.882181 8.068991\n7916 18.738525 -0.372991 0.838184 3.591748 -6.875589 2.957543 8.082715\n7917 18.744457 -0.248569 0.807207 3.563805 -6.446652 2.815278 7.963113\n7918 18.750593 -0.204119 0.803369 3.537939 -6.130426 2.632617 7.895580\n7919 18.756600 -0.153641 0.812124 3.466588 -5.833613 2.388046 7.782183\n7920 18.762708 -0.134176 0.823245 3.416669 -5.849325 2.367836 7.894527\n7921 18.768813 -0.105488 0.847799 3.290763 -6.118553 2.380189 7.971960\n7922 18.775281 -0.096050 0.861313 3.222725 -6.300277 2.379386 7.865334\n7923 18.780896 -0.107135 0.884797 3.074672 -6.457152 2.305321 7.612903\n7924 18.786722 -0.135291 0.891939 2.992948 -6.394015 2.215840 7.526577\n7925 18.792874 -0.237767 0.899785 2.825914 -6.036585 2.076307 7.649947\n7926 18.798729 -0.305858 0.901170 2.743523 -5.794183 2.126283 7.860099\n7927 18.804919 -0.455818 0.901530 2.588153 -5.461030 2.522691 8.215319\n7928 18.810845 -0.529676 0.901553 2.517552 -5.295404 2.714403 8.209841\n7929 18.816880 -0.675161 0.893752 2.380075 -4.856276 2.914467 7.933033\n7930 18.823005 -0.745760 0.882441 2.307310 -4.684992 2.982782 7.804818\n7931 18.829047 -0.886397 0.846356 2.145764 -4.244293 3.132107 7.827825\n7932 18.835380 -0.959672 0.820990 2.057553 -4.086812 3.281680 7.917895\n7933 18.841103 -1.111804 0.758552 1.882165 -4.001917 3.691152 8.007287\n7934 18.847182 -1.189377 0.723803 1.799157 -4.074449 3.898137 8.013007\n7935 18.853162 -1.341416 0.651521 1.644300 -4.436329 4.113615 7.979970\n7936 18.859220 -1.414079 0.615168 1.572306 -4.638591 4.128494 7.964484\n7937 18.865494 -1.546232 0.544530 1.435590 -4.991863 4.109113 7.928499\n7938 18.871378 -1.607149 0.510139 1.373567 -5.174997 4.074756 7.894351\n7939 18.877618 -1.730794 0.439364 1.277159 -5.532369 4.100571 7.828722\n7940 18.883503 -1.789368 0.402926 1.249216 -5.628707 4.190655 7.757406\n7941 18.889544 -1.876148 0.330143 1.212818 -6.014575 4.435311 7.749013\n7942 18.896197 -1.921920 0.292540 1.195987 -6.281550 4.525578 7.941268\n7943 18.901689 -1.997943 0.207609 1.137114 -6.387743 4.355675 8.064961\n7944 18.908294 -2.028169 0.156778 1.094832 -6.103097 4.072113 8.126628\n7945 18.913698 -2.095900 0.016233 0.995267 -5.040157 3.392998 8.418952\n7946 18.920228 -2.165132 -0.158508 0.891944 -3.822241 2.667263 8.840566\n7947 18.925790 -2.195584 -0.248847 0.841152 -3.305484 2.293355 9.093544\n7948 18.932324 -2.253316 -0.421307 0.731293 -2.984386 1.681682 9.289100\n7949 18.937840 -2.281488 -0.493942 0.667667 -3.184493 1.513700 9.206120\n7950 18.944256 -2.333062 -0.611085 0.517615 -3.943581 1.507303 8.981628\n7951 18.950074 -2.361170 -0.655423 0.434251 -4.353751 1.668698 8.794149\n7952 18.956599 -2.409566 -0.725276 0.258739 -4.919580 2.457404 8.562468\n7953 18.962030 -2.428225 -0.760785 0.167452 -5.034603 2.932970 8.547043\n7954 18.968706 -2.452943 -0.844246 -0.021601 -4.956686 3.391977 8.558792\n7955 18.974202 -2.461676 -0.893967 -0.117243 -4.770773 3.263210 8.599814\n7956 18.981053 -2.499388 -1.010702 -0.298419 -4.166914 2.697243 8.572252\n7957 18.987223 -2.529294 -1.074346 -0.375517 -3.853098 2.486502 8.533028\n7958 18.993200 -2.599075 -1.198683 -0.481181 -3.481760 2.322955 8.749510\n7959 18.999308 -2.638384 -1.255015 -0.507799 -3.449839 2.303361 9.006103\n7960 19.005161 -2.723139 -1.358341 -0.519669 -3.642689 2.329336 9.756645\n7961 19.011323 -2.757152 -1.391896 -0.513445 -3.735775 2.331106 10.000127\n7962 19.017435 -2.820297 -1.438512 -0.496452 -3.801765 2.274851 10.114653\n7963 19.023403 -2.850822 -1.453268 -0.487771 -3.797179 2.282664 10.014754\n7964 19.029341 -2.895523 -1.466486 -0.471279 -3.699341 2.532228 9.713329\n7965 19.035491 -2.899696 -1.466811 -0.465930 -3.618373 2.679346 9.584176\n7966 19.041484 -2.863194 -1.460236 -0.473133 -3.413848 2.649642 9.352055\n7967 19.047576 -2.826604 -1.454224 -0.491381 -3.340041 2.506418 9.216872\n7968 19.053576 -2.730643 -1.432816 -0.565420 -3.342982 2.203715 9.026661\n7969 19.059559 -2.675797 -1.413799 -0.619490 -3.319839 1.968538 8.999109\n7970 19.065664 -2.563150 -1.350989 -0.743905 -3.116208 1.258046 8.975863\n7971 19.071715 -2.504929 -1.306651 -0.804657 -2.963143 0.895669 8.956862\n7972 19.077605 -2.375652 -1.191846 -0.909223 -2.791206 0.237619 8.825469\n7973 19.083641 -2.304828 -1.121372 -0.952886 -2.912516 -0.103687 8.711657\n7974 19.090011 -2.155116 -0.958921 -1.033950 -3.419287 -0.701978 8.498946\n7975 19.095862 -2.079354 -0.867080 -1.074695 -3.663334 -0.917263 8.447570\n7976 19.101790 -1.931884 -0.659748 -1.154160 -3.965764 -1.123529 8.610031\n7977 19.108057 -1.865775 -0.544727 -1.189148 -3.999146 -1.123903 8.696256\n7978 19.113947 -1.755101 -0.302216 -1.245966 -3.890752 -0.896719 8.819754\n7979 19.120088 -1.709460 -0.183402 -1.268267 -3.769070 -0.759266 8.908633\n7980 19.125959 -1.624920 0.027672 -1.310833 -3.405477 -0.760216 9.198314\n7981 19.132089 -1.582196 0.111170 -1.334253 -3.210364 -0.849569 9.363720\n7982 19.138069 -1.495315 0.220771 -1.379745 -2.862257 -0.965686 9.531045\n7983 19.144161 -1.451596 0.248043 -1.397455 -2.687537 -0.961697 9.510689\n7984 19.150287 -1.362858 0.255429 -1.414407 -2.437263 -1.014892 9.504624\n7985 19.156893 -1.267547 0.213284 -1.408020 -2.426779 -1.362974 9.696287\n7986 19.162398 -1.218196 0.179617 -1.401421 -2.503150 -1.527641 9.792346\n7987 19.168887 -1.119134 0.096338 -1.385070 -2.760096 -1.708254 9.846840\n7988 19.174508 -1.070983 0.051243 -1.374963 -2.912561 -1.777668 9.810199\n7989 19.180918 -0.991267 -0.039149 -1.355114 -3.311819 -1.832532 9.770614\n7990 19.186638 -0.969708 -0.089234 -1.345712 -3.569529 -1.813366 9.765498\n7991 19.192885 -0.983015 -0.217763 -1.332427 -4.074236 -1.696295 9.832439\n7992 19.198584 -1.017191 -0.303495 -1.333429 -4.280165 -1.655342 9.962156\n7993 19.204915 -1.133609 -0.526955 -1.356319 -4.370250 -1.870413 10.426916\n7994 19.210633 -1.209159 -0.661567 -1.376629 -4.141721 -2.122181 10.679314\n7995 19.216921 -1.361391 -0.951168 -1.418616 -3.384411 -2.589504 10.850532\n7996 19.223054 -1.428186 -1.094747 -1.431322 -3.091317 -2.726359 10.740546\n7997 19.228935 -1.527039 -1.352173 -1.433308 -2.876204 -2.912684 10.332215\n7998 19.234945 -1.551013 -1.456744 -1.427168 -2.891179 -3.034427 10.152010\n7999 19.240935 -1.539906 -1.613248 -1.416120 -2.794127 -3.257568 9.903254\n8000 19.246917 -1.507279 -1.668567 -1.414398 -2.638277 -3.320278 9.751113\n8001 19.253079 -1.398151 -1.736427 -1.412758 -2.268164 -3.363071 9.443493\n8002 19.259059 -1.340313 -1.751629 -1.413830 -1.979606 -3.276941 9.218389\n8003 19.265121 -1.243505 -1.752382 -1.415511 -1.950299 -3.121117 8.919415\n8004 19.270986 -1.207125 -1.738710 -1.420900 -2.149918 -3.018516 8.869198\n8005 19.277101 -1.158344 -1.680937 -1.459758 -2.780928 -2.789691 8.932468\n8006 19.283114 -1.146700 -1.638710 -1.490827 -3.139763 -2.665049 8.903896\n8007 19.289171 -1.148523 -1.534706 -1.572479 -3.433904 -2.508455 8.747169\n8008 19.295330 -1.153661 -1.480202 -1.624678 -3.372339 -2.609779 8.740737\n8009 19.301259 -1.158373 -1.383062 -1.736015 -2.849603 -3.301002 8.835382\n8010 19.307220 -1.154280 -1.346628 -1.789502 -2.393718 -3.719349 8.925611\n8011 19.313293 -1.136553 -1.306279 -1.883160 -1.494827 -4.168714 8.956406\n8012 19.319327 -1.122285 -1.303365 -1.919935 -1.114585 -4.206060 8.931070\n8013 19.325352 -1.086091 -1.327793 -1.979212 -0.550639 -4.251213 8.949697\n8014 19.331406 -1.072487 -1.352952 -2.007567 -0.411527 -4.242443 8.953879\n8015 19.337407 -1.066166 -1.428862 -2.069288 -0.306710 -4.114202 8.990519\n8016 19.343539 -1.073919 -1.477201 -2.103887 -0.266926 -4.106102 9.102253\n8017 19.349669 -1.107993 -1.579298 -2.179923 -0.254746 -4.197049 9.466805\n8018 19.355675 -1.132161 -1.628311 -2.222609 -0.315423 -4.214484 9.571707\n8019 19.361715 -1.182726 -1.715451 -2.326554 -0.500277 -4.475549 9.519268\n8020 19.367704 -1.202159 -1.751392 -2.389312 -0.525092 -4.824462 9.439419\n8021 19.373761 -1.221087 -1.799367 -2.530694 -0.505828 -5.605459 9.126713\n8022 19.379713 -1.220819 -1.807968 -2.601430 -0.563028 -5.872246 8.850583\n8023 19.385770 -1.189327 -1.788397 -2.718723 -0.499894 -6.224842 8.411191\n8024 19.391840 -1.158697 -1.756683 -2.756496 -0.313540 -6.321856 8.328288\n8025 19.397869 -1.077097 -1.652777 -2.779408 0.147683 -6.206061 8.300552\n8026 19.403904 -1.037520 -1.589918 -2.768631 0.342361 -6.001325 8.204517\n8027 19.409975 -0.981847 -1.469144 -2.723856 0.603115 -5.509363 7.986015\n8028 19.416123 -0.967190 -1.418310 -2.698214 0.698938 -5.307962 8.001507\n8029 19.422121 -0.961293 -1.343369 -2.661468 0.982260 -5.016336 8.277138\n8030 19.428098 -0.967195 -1.320205 -2.656237 1.165083 -4.926088 8.456433\n8031 19.434113 -0.982849 -1.298108 -2.677716 1.569383 -4.920326 8.697056\n8032 19.440231 -0.993763 -1.295027 -2.706380 1.744402 -5.008257 8.774029\n8033 19.446144 -1.009933 -1.299891 -2.807612 1.932766 -5.159180 8.850952\n8034 19.452153 -1.013062 -1.305371 -2.883605 1.925079 -5.217774 8.788611\n8035 19.458331 -0.998279 -1.321073 -3.086119 1.698359 -5.508652 8.604332\n8036 19.464413 -0.976130 -1.332492 -3.206800 1.502959 -5.749715 8.590249\n8037 19.470421 -0.891179 -1.352135 -3.465968 1.218196 -6.070193 8.627880\n8038 19.476407 -0.827731 -1.357780 -3.593041 1.169572 -6.058475 8.668624\n8039 19.482485 -0.668455 -1.365828 -3.844149 1.422999 -5.825893 8.453856\n8040 19.488756 -0.597048 -1.369794 -3.938502 1.705216 -5.740942 8.283521\n8041 19.494670 -0.469277 -1.385847 -4.101025 2.414038 -5.394639 7.982497\n8042 19.500608 -0.416931 -1.398254 -4.170840 2.762009 -5.023907 7.838905\n8043 19.506531 -0.330411 -1.426667 -4.285890 3.404681 -3.946156 7.713940\n8044 19.512688 -0.292959 -1.437926 -4.328345 3.662421 -3.482657 7.727951\n8045 19.518762 -0.238668 -1.439383 -4.382140 4.128228 -3.237006 7.610286\n8046 19.524746 -0.226105 -1.429771 -4.396986 4.371489 -3.366588 7.505270\n8047 19.530743 -0.226174 -1.387215 -4.405302 4.844434 -3.661299 7.319874\n8048 19.537234 -0.226858 -1.349881 -4.398689 5.016609 -3.663180 7.295523\n8049 19.542906 -0.209251 -1.244299 -4.364928 5.163104 -3.324772 7.173965\n8050 19.549405 -0.187598 -1.180674 -4.339432 5.201429 -3.125956 6.995342\n8051 19.555293 -0.112220 -1.043047 -4.277443 5.348040 -2.879218 6.645582\n8052 19.561552 -0.003635 -0.903794 -4.193777 5.487781 -2.774221 6.411032\n8053 19.567205 0.061706 -0.835478 -4.139601 5.511230 -2.653744 6.280975\n8054 19.573670 0.209362 -0.706278 -4.010072 5.432078 -2.429991 6.343746\n8055 19.579508 0.283987 -0.647712 -3.940191 5.383077 -2.444633 6.514934\n8056 19.585644 0.429904 -0.547950 -3.810995 5.386550 -2.426306 6.889436\n8057 19.591295 0.500025 -0.511680 -3.756931 5.444108 -2.285222 7.037586\n8058 19.597712 0.622257 -0.467395 -3.670216 5.553567 -1.961802 7.302645\n8059 19.603407 0.672679 -0.455396 -3.636850 5.564766 -1.849442 7.458802\n8060 19.609819 0.756347 -0.442088 -3.592271 5.403535 -1.692701 7.594555\n8061 19.615426 0.793419 -0.437654 -3.581531 5.242023 -1.649098 7.515625\n8062 19.622160 0.863546 -0.433831 -3.586974 5.012721 -1.692268 7.421583\n8063 19.627490 0.898111 -0.435307 -3.603852 5.029496 -1.803009 7.425207\n8064 19.633838 0.974321 -0.444216 -3.661533 5.344722 -2.075641 7.555798\n8065 19.639646 1.017522 -0.455133 -3.697738 5.611066 -2.123716 7.602665\n8066 19.645881 1.114562 -0.487950 -3.773628 6.168692 -1.859924 7.429025\n8067 19.651597 1.166739 -0.508129 -3.809144 6.383703 -1.506449 7.233968\n8068 19.657999 1.276260 -0.550162 -3.876774 6.636895 -0.602369 6.888396\n8069 19.663575 1.335425 -0.565746 -3.913045 6.681154 -0.243294 6.805117\n8070 19.669980 1.461442 -0.575917 -3.992631 6.722453 0.210648 6.851895\n8071 19.675737 1.525667 -0.568856 -4.032330 6.773695 0.391629 6.820034\n8072 19.681890 1.634324 -0.528615 -4.094315 6.910651 0.884421 6.625895\n8073 19.688151 1.668589 -0.499371 -4.111655 7.036443 1.266031 6.529452\n8074 19.693893 1.706397 -0.429681 -4.122870 7.363947 1.967999 6.458891\n8075 19.700304 1.716111 -0.392209 -4.123281 7.426280 2.083510 6.545914\n8076 19.705911 1.711056 -0.318449 -4.130363 7.328026 1.856240 6.728360\n8077 19.712035 1.694851 -0.280879 -4.138454 7.266436 1.790084 6.688458\n8078 19.718173 1.656196 -0.199134 -4.143192 7.164271 2.050163 6.464297\n8079 19.724123 1.635136 -0.152932 -4.131209 7.128597 2.200363 6.347598\n8080 19.730105 1.594004 -0.050481 -4.079447 7.124846 2.257868 6.294448\n8081 19.736079 1.582958 0.002595 -4.044019 7.146219 2.225474 6.350302\n8082 19.742247 1.600636 0.106513 -3.961308 7.294752 2.172081 6.596667\n8083 19.748191 1.627587 0.156547 -3.913885 7.365083 2.189905 6.753247\n8084 19.754437 1.723908 0.255530 -3.795537 7.278065 2.486790 6.969224\n8085 19.760284 1.789037 0.307316 -3.720168 7.108205 2.861226 6.949862\n8086 19.766409 1.934354 0.415810 -3.539984 6.571645 4.011591 6.566386\n8087 19.772407 2.009534 0.469595 -3.439933 6.288025 4.553807 6.327393\n8088 19.778438 2.154675 0.566148 -3.241985 5.949210 5.050426 6.045331\n8089 19.784458 2.222648 0.608340 -3.153643 5.915649 5.045908 6.018908\n8090 19.790474 2.332349 0.686482 -3.003182 6.034484 4.986032 6.007160\n8091 19.796433 2.366419 0.725294 -2.936999 6.085789 4.960570 5.955220\n8092 19.802539 2.383261 0.824639 -2.806703 5.914453 4.550742 6.015180\n8093 19.808526 2.367870 0.873858 -2.763439 5.757984 4.218886 6.182271\n8094 19.814703 2.324321 0.974699 -2.721898 5.514065 3.529036 6.501137\n8095 19.820751 2.308458 1.022387 -2.723789 5.492781 3.321896 6.628066\n8096 19.826672 2.303873 1.100037 -2.756319 5.563865 3.648512 6.654848\n8097 19.832955 2.316979 1.128263 -2.777324 5.577551 4.268796 6.492092\n8098 19.838717 2.361947 1.161065 -2.811772 5.538753 5.956961 6.073312\n8099 19.844915 2.388153 1.167389 -2.822725 5.506441 6.724056 5.877481\n8100 19.850900 2.437360 1.164904 -2.833508 5.491490 7.665774 5.708849\n8101 19.856844 2.456578 1.156165 -2.833971 5.540385 7.816936 5.715948\n8102 19.862949 2.476587 1.122241 -2.818099 5.693303 7.750907 5.881007\n8103 19.868933 2.466365 1.099486 -2.795513 5.784505 7.616033 5.926504\n8104 19.875240 2.398887 1.045408 -2.707170 5.752281 7.301409 5.908214\n8105 19.881123 2.336192 1.016179 -2.642913 5.615708 7.106855 5.901914\n8106 19.887140 2.172814 0.957722 -2.497143 5.256292 6.685494 6.033562\n8107 19.893273 2.080784 0.931483 -2.422567 5.077776 6.471386 6.170991\n8108 19.899203 1.915568 0.892575 -2.269178 4.808889 6.202428 6.387839\n8109 19.905186 1.853536 0.885764 -2.186929 4.671138 6.228810 6.364625\n8110 19.911238 1.782041 0.906152 -2.000886 4.346716 6.619607 5.981200\n8111 19.917240 1.768979 0.934938 -1.896804 4.201675 6.915518 5.711306\n8112 19.923523 1.784301 1.026986 -1.683610 3.919230 7.758456 5.209253\n8113 19.929506 1.808542 1.089690 -1.584832 3.680721 8.405581 4.955142\n8114 19.935444 1.877017 1.236004 -1.422946 3.148718 9.658047 4.329266\n8115 19.941471 1.910780 1.315798 -1.361974 2.986909 9.986768 3.960887\n8116 19.947545 1.948996 1.482872 -1.268750 2.892225 10.121166 3.410269\n8117 19.953866 1.946022 1.568056 -1.228759 2.889423 10.044563 3.281172\n8118 19.959642 1.886809 1.743175 -1.148522 2.950427 9.616886 3.329752\n8119 19.965641 1.830786 1.832802 -1.106532 3.093517 9.266953 3.442326\n8120 19.971583 1.670189 2.009096 -1.019575 3.640939 8.501478 3.672550\n8121 19.977691 1.573056 2.093697 -0.975403 3.888769 8.155379 3.801229\n8122 19.983905 1.379983 2.259089 -0.883852 3.906548 7.740098 4.035662\n8123 19.989704 1.299257 2.344004 -0.832743 3.669559 7.725304 4.102736\n8124 19.995899 1.182671 2.529567 -0.709977 2.992927 8.030594 4.009706\n8125 20.001887 1.144928 2.630355 -0.638078 2.633926 8.279750 3.859847\n8126 20.008149 1.101114 2.841001 -0.483813 1.875358 8.887315 3.538628\n8127 20.013975 1.090608 2.950288 -0.407597 1.456725 9.264947 3.393490\n8128 20.020302 1.070125 3.168228 -0.266512 0.632864 10.079611 3.091677\n8129 20.026062 1.052221 3.271154 -0.201602 0.323742 10.396521 2.922501\n8130 20.032158 0.994429 3.456297 -0.076343 0.017496 10.607125 2.695835\n8131 20.038682 0.895226 3.606931 0.055619 -0.031306 10.373713 2.865277\n8132 20.044281 0.828822 3.670303 0.127150 0.011328 10.180171 3.034569\n8133 20.050786 0.662379 3.774166 0.280058 0.281468 9.724735 3.514397\n8134 20.056284 0.563222 3.812269 0.358911 0.457357 9.488976 3.752289\n8135 20.062722 0.362004 3.863836 0.515017 0.742638 9.051437 4.172380\n8136 20.068345 0.265604 3.878998 0.592130 0.843664 8.888030 4.435283\n8137 20.074828 0.111890 3.891207 0.747666 0.946603 8.796374 4.657156\n8138 20.080383 0.062031 3.891536 0.827360 0.979175 8.805899 4.631387\n8139 20.086957 0.013994 3.882006 0.983952 1.002733 8.798746 4.524567\n8140 20.092423 0.009872 3.875862 1.056727 0.897057 8.823515 4.455352\n8141 20.098893 0.036106 3.869677 1.181333 0.386329 8.957651 4.344831\n8142 20.104690 0.060677 3.868389 1.230648 0.050319 9.041512 4.253749\n8143 20.110888 0.127733 3.868632 1.304307 -0.581792 9.278545 3.957149\n8144 20.116599 0.160742 3.867498 1.332190 -0.806836 9.431071 3.874295\n8145 20.122853 0.231266 3.860545 1.374114 -1.083072 9.678827 3.673660\n8146 20.128733 0.261482 3.854413 1.388900 -1.148489 9.758272 3.677572\n8147 20.135042 0.292168 3.830873 1.402418 -1.057459 9.652042 3.751624\n8148 20.140805 0.288983 3.815461 1.401448 -0.901090 9.531415 3.838256\n8149 20.146897 0.239863 3.776806 1.390579 -0.333530 9.358974 4.150344\n8150 20.152938 0.195518 3.753523 1.384846 0.064947 9.239985 4.296816\n8151 20.159002 0.089518 3.700994 1.377380 0.842600 8.982418 4.439120\n8152 20.165050 0.028621 3.673224 1.375343 1.079739 8.885988 4.461034\n8153 20.171176 -0.106408 3.617223 1.370893 1.078242 8.588319 4.517085\n8154 20.177025 -0.174604 3.593264 1.364772 1.030463 8.452099 4.481271\n8155 20.183182 -0.305695 3.550850 1.348760 0.883073 8.535811 4.504516\n8156 20.188914 -0.369093 3.532054 1.342032 0.801512 8.731438 4.470142\n8157 20.195384 -0.483155 3.509725 1.330250 0.734030 9.217486 4.411115\n8158 20.201051 -0.531428 3.504610 1.329088 0.597121 9.437226 4.478666\n8159 20.207204 -0.611606 3.512334 1.340917 0.276415 9.720010 4.459570\n8160 20.213253 -0.643233 3.525209 1.351085 0.062599 9.840340 4.428692\n8161 20.219476 -0.712416 3.563078 1.388288 -0.637407 9.891638 4.111987\n8162 20.225299 -0.746189 3.588664 1.416656 -1.010810 9.770135 3.931171\n8163 20.231291 -0.821947 3.652842 1.489574 -1.547568 9.573116 3.842273\n8164 20.237359 -0.858736 3.687856 1.535866 -1.742379 9.619514 3.764666\n8165 20.243355 -0.937830 3.757122 1.642366 -1.710000 9.632451 3.573737\n8166 20.249441 -0.980296 3.784473 1.695878 -1.549362 9.599574 3.410213\n8167 20.255448 -1.076068 3.825555 1.795417 -1.498390 9.596473 3.393254\n8168 20.261606 -1.124004 3.837906 1.837410 -1.471341 9.542442 3.479803\n8169 20.267582 -1.212653 3.854477 1.897777 -1.229385 9.416259 3.637464\n8170 20.273564 -1.262993 3.855682 1.925559 -1.143429 9.485530 3.862288\n8171 20.279570 -1.351141 3.848376 1.980339 -0.981378 9.708852 4.073022\n8172 20.285927 -1.396050 3.845040 1.999173 -0.926522 9.750964 4.312946\n8173 20.291783 -1.480557 3.823230 2.024316 -0.940395 9.479280 4.479136\n8174 20.297746 -1.524944 3.809514 2.028374 -0.882340 9.296573 4.538071\n8175 20.303803 -1.612821 3.770738 2.017120 -0.834584 9.125636 4.854372\n8176 20.309904 -1.648749 3.751422 2.008738 -0.809411 9.083685 4.822853\n8177 20.315977 -1.724682 3.714074 1.997178 -0.742298 9.046540 5.098812\n8178 20.321981 -1.764609 3.692201 1.990803 -0.721183 9.023718 5.152449\n8179 20.328061 -1.831630 3.652287 1.974813 -0.716537 8.960656 5.076677\n8180 20.333924 -1.857676 3.628345 1.960714 -0.768300 8.863214 5.059433\n8181 20.340047 -1.923097 3.570036 1.918065 -0.894795 8.819267 5.158952\n8182 20.346120 -1.945251 3.540888 1.893020 -0.912305 8.927186 5.256425\n8183 20.352139 -1.978858 3.480531 1.851289 -0.583355 9.052401 5.505691\n8184 20.358060 -2.001535 3.445863 1.836765 -0.399949 9.035735 5.539433\n8185 20.364202 -2.052581 3.380171 1.824749 -0.228109 8.884209 5.696433\n8186 20.370243 -2.082988 3.349738 1.824553 -0.199632 8.772417 5.833611\n8187 20.376338 -2.149834 3.296802 1.832150 -0.369897 8.533173 5.786810\n8188 20.382349 -2.183118 3.276513 1.840294 -0.541245 8.398137 5.670305\n8189 20.388418 -2.244598 3.246402 1.860766 -1.011725 8.212485 5.417109\n8190 20.394444 -2.271656 3.239410 1.871542 -1.293345 8.170153 5.317705\n8191 20.400532 -2.315386 3.239991 1.890666 -1.681790 8.023223 5.304796\n8192 20.406527 -2.332925 3.244512 1.894248 -1.773868 7.904600 5.353142\n8193 20.412543 -2.353101 3.256961 1.880933 -1.869394 7.657503 5.483700\n8194 20.418789 -2.355571 3.262725 1.863665 -1.896784 7.556848 5.606753\n8195 20.424774 -2.353595 3.266634 1.814894 -2.014698 7.397885 5.786538\n8196 20.430674 -2.341733 3.264407 1.786720 -2.100238 7.281375 5.809801\n8197 20.436908 -2.298735 3.248704 1.728144 -2.166252 7.012338 5.953043\n8198 20.442750 -2.272896 3.233188 1.699461 -2.112763 6.961647 6.073938\n8199 20.448767 -2.210974 3.193717 1.645517 -1.979195 6.886543 6.342424\n8200 20.454767 -2.177951 3.167729 1.617449 -1.913761 6.754148 6.459063\n8201 20.460775 -2.113424 3.098877 1.549971 -1.919505 6.367468 6.506282\n8202 20.467450 -2.052994 3.012543 1.466513 -1.956437 6.040880 6.847147\n8203 20.473063 -2.022028 2.966068 1.420410 -1.980233 5.948966 7.134390\n8204 20.479490 -1.986966 2.919285 1.373466 -2.090496 5.897569 7.413340\n8205 20.485228 -1.918599 2.824470 1.277908 -2.238097 5.778781 7.724242\n8206 20.491567 -1.873703 2.715829 1.174388 -2.449114 5.633099 7.704558\n8207 20.497228 -1.861010 2.654117 1.119388 -2.502683 5.547820 7.679359\n8208 20.503652 -1.848633 2.512963 1.004516 -2.476563 5.488836 7.818959\n8209 20.509259 -1.846500 2.432960 0.948888 -2.402792 5.561352 7.921411\n8210 20.515630 -1.851535 2.262148 0.853271 -2.340270 5.642522 8.040113\n8211 20.521172 -1.862861 2.173052 0.814033 -2.427131 5.576892 8.015683\n8212 20.527965 -1.911764 1.967758 0.736362 -2.968761 5.306666 7.874909\n8213 20.533504 -1.940052 1.876826 0.702484 -3.241260 5.290620 7.877838\n8214 20.539672 -1.987844 1.695740 0.628094 -3.571851 5.392638 7.966634\n8215 20.545455 -1.998881 1.603567 0.588442 -3.624244 5.412495 8.038034\n8216 20.551834 -1.994820 1.415698 0.503335 -3.627607 5.333530 8.136617\n8217 20.557644 -1.981116 1.321140 0.456222 -3.606913 5.248305 8.169704\n8218 20.563932 -1.940466 1.130726 0.354087 -3.441276 5.013806 8.287974\n8219 20.569581 -1.915654 1.034526 0.300930 -3.300192 4.868574 8.338971\n8220 20.575884 -1.851825 0.844107 0.193769 -3.016456 4.492500 8.494457\n8221 20.581614 -1.815100 0.753206 0.143188 -2.908201 4.313422 8.608274\n8222 20.588018 -1.736348 0.586919 0.052175 -2.817477 4.082371 8.733498\n8223 20.593598 -1.697477 0.513509 0.012633 -2.843581 4.025029 8.739820\n8224 20.599867 -1.631871 0.389494 -0.055197 -2.977380 4.066567 8.722471\n8225 20.605865 -1.609059 0.338042 -0.085952 -3.050541 4.112909 8.690495\n8226 20.611970 -1.590453 0.250875 -0.144284 -3.193592 4.093761 8.586832\n8227 20.618094 -1.595441 0.210489 -0.173702 -3.278549 4.077848 8.512288\n8228 20.624024 -1.634416 0.128015 -0.239898 -3.499992 4.283386 8.349840\n8229 20.630018 -1.666407 0.083186 -0.278351 -3.581204 4.417636 8.297400\n8230 20.636094 -1.758082 -0.014662 -0.368718 -3.589821 4.379123 8.309763\n8231 20.642104 -1.817589 -0.067437 -0.421631 -3.516614 4.188657 8.365885\n8232 20.648138 -1.960266 -0.176048 -0.538827 -3.299625 3.642495 8.524436\n8233 20.654026 -2.039006 -0.229604 -0.598405 -3.186976 3.338734 8.631622\n8234 20.660347 -2.199764 -0.329179 -0.709175 -3.097239 2.788271 8.821794\n8235 20.666045 -2.275615 -0.373231 -0.757939 -3.176347 2.620550 8.911262\n8236 20.672124 -2.402468 -0.444596 -0.840630 -3.495267 2.483455 9.077617\n8237 20.678299 -2.452784 -0.471876 -0.876427 -3.657514 2.482264 9.141821\n8238 20.684466 -2.535103 -0.516549 -0.939821 -3.869660 2.583655 9.123917\n8239 20.690471 -2.569996 -0.536382 -0.967926 -3.859679 2.639881 9.058029\n8240 20.696347 -2.634377 -0.573391 -1.016649 -3.484379 2.676309 8.946311\n8241 20.702483 -2.664205 -0.589272 -1.036340 -3.145245 2.768311 8.902205\n8242 20.708459 -2.705068 -0.613811 -1.061640 -2.559336 3.312619 8.926370\n8243 20.714583 -2.712264 -0.620267 -1.068328 -2.425653 3.626924 8.973448\n8244 20.720488 -2.696341 -0.619349 -1.079635 -2.525327 3.859948 9.150168\n8245 20.726674 -2.678848 -0.613562 -1.085506 -2.766904 3.732969 9.228658\n8246 20.732684 -2.629754 -0.589373 -1.094053 -3.380143 3.281148 9.282184\n8247 20.738717 -2.597760 -0.569735 -1.093357 -3.642296 3.066248 9.302299\n8248 20.744649 -2.517513 -0.520124 -1.070780 -3.974664 2.611835 9.358781\n8249 20.750772 -2.469893 -0.493688 -1.050713 -4.023579 2.316362 9.384702\n8250 20.756794 -2.372205 -0.451270 -1.013093 -3.927905 1.578797 9.381568\n8251 20.762701 -2.329619 -0.441912 -1.001979 -3.804105 1.193578 9.350817\n8252 20.768945 -2.275038 -0.458640 -1.002940 -3.496442 0.333939 9.387007\n8253 20.774804 -2.270771 -0.483247 -1.014520 -3.429953 -0.135393 9.523858\n8254 20.780996 -2.299444 -0.554955 -1.050701 -3.477346 -0.862441 9.932715\n8255 20.786971 -2.325844 -0.596333 -1.071078 -3.482642 -1.105006 10.100612\n8256 20.792952 -2.379239 -0.687962 -1.110114 -3.454967 -1.461336 10.339687\n8257 20.799159 -2.400310 -0.739773 -1.131788 -3.469206 -1.627902 10.435159\n8258 20.805154 -2.417753 -0.856320 -1.196768 -3.556262 -1.805943 10.583318\n8259 20.811167 -2.410470 -0.920767 -1.241830 -3.548617 -1.668388 10.531510\n8260 20.817335 -2.356819 -1.061489 -1.343938 -3.343297 -1.058345 10.165714\n8261 20.823366 -2.310852 -1.134886 -1.393433 -3.172987 -0.822045 10.032827\n8262 20.829397 -2.181696 -1.277249 -1.476975 -2.765531 -0.625485 10.167791\n8263 20.835236 -2.100947 -1.340171 -1.509460 -2.557992 -0.514459 10.272168\n8264 20.841399 -1.940789 -1.439319 -1.560884 -2.235256 -0.182398 10.081428\n8265 20.847381 -1.877223 -1.477193 -1.584091 -2.129415 -0.107296 9.822414\n8266 20.853479 -1.789720 -1.527991 -1.629972 -2.114459 -0.323431 9.520548\n8267 20.859529 -1.758809 -1.536433 -1.651046 -2.139956 -0.522705 9.528999\n8268 20.865493 -1.698797 -1.510318 -1.672558 -2.134457 -0.887348 9.527739\n8269 20.871461 -1.665600 -1.475579 -1.666081 -2.107887 -1.027264 9.399817\n8270 20.877586 -1.591449 -1.370499 -1.625294 -2.228821 -1.290502 9.052485\n8271 20.882604 -1.553991 -1.307832 -1.606232 -2.348991 -1.466583 8.970517\n8272 20.888748 -1.478214 -1.186972 -1.603651 -2.552306 -1.945453 9.082815\n8273 20.894819 -1.433864 -1.136796 -1.623376 -2.588161 -2.179406 9.251444\n8274 20.900947 -1.325227 -1.071640 -1.694591 -2.513611 -2.438162 9.541677\n8275 20.906796 -1.261660 -1.059271 -1.738495 -2.486112 -2.405019 9.618791\n8276 20.912858 -1.122482 -1.064642 -1.827318 -2.424817 -2.170944 9.721551\n8277 20.918910 -1.055609 -1.075795 -1.873499 -2.288707 -2.163018 9.727408\n8278 20.924911 -0.941365 -1.107466 -1.972002 -1.862317 -2.314557 9.587051\n8279 20.931259 -0.887583 -1.129572 -2.034538 -1.550886 -2.258252 9.438780\n8280 20.937031 -0.822836 -1.161605 -2.122637 -1.025073 -1.778940 9.269535\n8281 20.942984 -0.795925 -1.172761 -2.151095 -0.736936 -1.507705 9.188550\n8282 20.949133 -0.748765 -1.182326 -2.161363 -0.084613 -1.238507 9.122755\n8283 20.955131 -0.729221 -1.180058 -2.145599 0.228061 -1.276116 9.117852\n8284 20.961327 -0.702813 -1.159813 -2.087950 0.666584 -1.621328 9.129184\n8285 20.967262 -0.693589 -1.142357 -2.051001 0.763812 -1.861556 9.106914\n8286 20.973259 -0.666949 -1.094650 -1.964506 0.747353 -2.240113 8.982097\n8287 20.979326 -0.641163 -1.065698 -1.912579 0.708862 -2.307308 8.887855\n8288 20.985406 -0.548677 -1.002978 -1.781318 0.710062 -2.232183 8.675402\n8289 20.991383 -0.479874 -0.970841 -1.701855 0.734393 -2.208168 8.608565\n8290 20.997534 -0.310614 -0.907641 -1.528027 0.780024 -2.399305 8.537756\n8291 21.003361 -0.220020 -0.876842 -1.441061 0.773225 -2.525653 8.556087\n8292 21.009411 -0.037994 -0.811369 -1.274683 0.698536 -2.552950 8.694443\n8293 21.015443 0.053541 -0.770873 -1.194048 0.746529 -2.445583 8.743968\n8294 21.021656 0.234230 -0.670165 -1.028429 1.151081 -2.151440 8.676465\n8295 21.027799 0.322268 -0.611013 -0.941704 1.435812 -2.132352 8.550177\n8296 21.034184 0.484171 -0.475045 -0.771689 1.850837 -2.547617 8.320430\n8297 21.039794 0.557002 -0.399085 -0.694253 1.927831 -2.818846 8.276015\n8298 21.045747 0.692443 -0.230214 -0.556407 1.915993 -3.065980 8.178275\n8299 21.051934 0.754891 -0.139371 -0.494848 1.805916 -3.128050 8.119502\n8300 21.057897 0.859763 0.042595 -0.391376 1.435228 -3.400657 8.061375\n8301 21.064075 0.907112 0.130790 -0.353615 1.266234 -3.561248 8.065991\n8302 21.070015 1.004353 0.297325 -0.305738 1.148813 -3.848408 8.245468\n8303 21.076145 1.054169 0.373426 -0.292925 1.223092 -3.953877 8.398685\n8304 21.082022 1.160347 0.509313 -0.284020 1.413757 -3.988484 8.790364\n8305 21.088075 1.219321 0.567754 -0.285267 1.407304 -3.929277 9.025704\n8306 21.094153 1.355323 0.658986 -0.297520 1.190230 -3.713746 9.424211\n8307 21.100230 1.434986 0.687752 -0.310622 1.085191 -3.538487 9.605185\n8308 21.106195 1.621686 0.703960 -0.352810 1.003264 -3.192937 10.095004\n8309 21.112258 1.726775 0.691102 -0.378063 0.731121 -3.085501 10.378964\n8310 21.118423 1.970933 0.632082 -0.436173 0.169022 -2.719722 10.766011\n8311 21.124791 2.220743 0.550185 -0.496873 -0.159001 -2.534701 10.687799\n8312 21.130437 2.332224 0.511652 -0.519532 -0.258099 -2.590178 10.479001\n8313 21.137111 2.518066 0.451858 -0.564509 -0.384018 -2.781397 10.434973\n8314 21.142454 2.591828 0.433213 -0.589045 -0.483164 -2.868993 10.564297\n8315 21.148907 2.696996 0.415055 -0.624347 -0.549348 -2.924258 10.863308\n8316 21.154446 2.720939 0.404586 -0.634563 -0.474195 -2.859185 11.009215\n8317 21.161131 2.715323 0.365607 -0.644926 -0.271882 -2.540446 11.288979\n8318 21.166663 2.692834 0.336555 -0.645230 -0.138819 -2.354767 11.490951\n8319 21.173018 2.608029 0.253202 -0.648415 0.095301 -2.120516 11.778371\n8320 21.178731 2.553961 0.200103 -0.655629 0.153908 -2.032465 11.811718\n8321 21.184988 2.442899 0.074838 -0.678370 0.280058 -1.800269 11.906006\n8322 21.190815 2.388017 0.004156 -0.693236 0.369156 -1.643178 12.026402\n8323 21.196890 2.279014 -0.144117 -0.723266 0.430443 -1.297964 12.318434\n8324 21.202737 2.224921 -0.219960 -0.736441 0.385802 -1.133325 12.386720\n8325 21.208953 2.113649 -0.377866 -0.762749 0.128622 -0.856368 12.359538\n8326 21.214911 2.059324 -0.461122 -0.775440 -0.025154 -0.824969 12.277461\n8327 21.221063 1.962728 -0.642600 -0.792345 -0.047155 -0.846352 12.226701\n8328 21.227135 1.930484 -0.743660 -0.791829 0.091344 -0.762368 12.251313\n8329 21.233144 1.917852 -0.959467 -0.760908 0.503926 -0.347154 12.366248\n8330 21.239412 1.932469 -1.069764 -0.730140 0.723020 -0.147510 12.444406\n8331 21.245122 1.971125 -1.281307 -0.649328 1.077806 0.221318 12.339430\n8332 21.251206 1.988600 -1.377562 -0.605422 1.205362 0.506668 12.136977\n8333 21.257315 2.014876 -1.542828 -0.527190 1.419979 1.209861 11.682389\n8334 21.263269 2.022290 -1.611198 -0.499502 1.512013 1.458274 11.533413\n8335 21.269547 2.027788 -1.723290 -0.473965 1.558325 1.681268 11.339460\n8336 21.275342 2.025376 -1.768622 -0.475935 1.507721 1.729119 11.212979\n8337 21.281329 1.995579 -1.837970 -0.507206 1.432155 1.683404 10.797867\n8338 21.287391 1.958390 -1.862833 -0.535663 1.344776 1.543532 10.579035\n8339 21.293581 1.835499 -1.894883 -0.621960 0.943201 0.985746 10.431803\n8340 21.299429 1.763050 -1.903669 -0.683867 0.694482 0.669256 10.465502\n8341 21.305499 1.625515 -1.919094 -0.839922 0.350671 0.301018 10.413603\n8342 21.311396 1.564183 -1.930989 -0.925621 0.310345 0.307288 10.258957\n8343 21.317786 1.467824 -1.970779 -1.097980 0.365183 0.576407 9.914207\n8344 21.323637 1.434318 -2.000785 -1.183216 0.392305 0.748568 9.799195\n8345 21.329722 1.392121 -2.100222 -1.378422 0.554606 0.999981 9.716552\n8346 21.335756 1.384426 -2.160915 -1.468455 0.665147 1.118087 9.714224\n8347 21.342008 1.394738 -2.304342 -1.647086 0.927042 1.574640 9.726016\n8348 21.348007 1.416308 -2.382957 -1.732150 1.063923 1.847672 9.742050\n8349 21.353854 1.490789 -2.544907 -1.892824 1.162444 2.129069 9.670866\n8350 21.360138 1.538228 -2.627090 -1.970101 1.115488 2.107174 9.537943\n8351 21.366008 1.648015 -2.791650 -2.124750 1.030439 2.065662 9.161582\n8352 21.371982 1.709104 -2.872837 -2.201052 0.851045 2.028108 9.067076\n8353 21.378012 1.838848 -3.028255 -2.346442 0.524262 1.981267 9.141929\n8354 21.384134 1.918733 -3.102375 -2.410537 0.511461 2.108452 9.211230\n8355 21.390252 2.085614 -3.244185 -2.491847 0.736400 2.504895 8.913817\n8356 21.396081 2.169002 -3.316126 -2.504053 1.026869 2.747173 8.659044\n8357 21.402275 2.331120 -3.461056 -2.476043 1.570642 3.346252 8.130075\n8358 21.408239 2.408486 -3.528525 -2.438537 1.763022 3.686489 7.955415\n8359 21.414395 2.540570 -3.651318 -2.336273 2.020534 4.375721 7.653214\n8360 21.420232 2.587963 -3.703714 -2.279922 2.077996 4.737143 7.373135\n8361 21.426525 2.634360 -3.783404 -2.171386 2.049198 5.221683 6.819496\n8362 21.432335 2.628594 -3.811671 -2.128393 1.990988 5.211891 6.640896\n8363 21.438436 2.553683 -3.843047 -2.085337 1.869832 4.896049 6.486767\n8364 21.445543 2.489145 -3.848568 -2.087355 1.801545 4.727091 6.484954\n8365 21.451634 2.309058 -3.845402 -2.136009 1.593174 4.489045 6.351179\n8366 21.457735 2.091190 -3.829528 -2.232919 1.410372 4.368337 6.135693\n8367 21.463524 1.978632 -3.817557 -2.290490 1.417154 4.281565 6.046918\n8368 21.469592 1.778851 -3.780281 -2.404416 1.916796 4.262844 5.841563\n8369 21.475524 1.706261 -3.754287 -2.451016 2.368109 4.507789 5.736053\n8370 21.481910 1.617687 -3.681918 -2.503134 3.288867 5.355066 5.334206\n8371 21.487652 1.608589 -3.637343 -2.509839 3.678863 5.829623 5.084296\n8372 21.493842 1.639345 -3.537423 -2.497093 4.072680 6.614389 4.617660\n8373 21.499739 1.679096 -3.480838 -2.484841 4.141340 6.904739 4.454813\n8374 21.505888 1.791036 -3.352582 -2.463205 4.208003 7.405886 4.180876\n8375 21.511898 1.848400 -3.284413 -2.453042 4.208266 7.613225 3.958859\n8376 21.518014 1.929311 -3.151451 -2.433622 4.267341 7.821675 3.677787\n8377 21.523956 1.951517 -3.091904 -2.426321 4.198097 7.826731 3.718212\n8378 21.529960 1.953785 -2.982331 -2.423155 4.193294 7.570834 3.870523\n8379 21.536115 1.937047 -2.931516 -2.426491 4.350693 7.386689 3.873006\n8380 21.542116 1.864769 -2.828325 -2.428662 4.968303 7.406443 3.548128\n8381 21.548210 1.816375 -2.767594 -2.421049 5.275084 7.669676 3.335768\n8382 21.554232 1.717360 -2.609176 -2.379187 5.523139 8.579576 2.846143\n8383 21.560238 1.675487 -2.507677 -2.343651 5.444767 9.120025 2.541281\n8384 21.566333 1.597825 -2.264227 -2.246719 5.105865 10.038090 1.804981\n8385 21.572238 1.554697 -2.126612 -2.187302 4.922957 10.303918 1.431533\n8386 21.578522 1.439743 -1.832066 -2.044192 4.638745 10.473839 0.864034\n8387 21.584458 1.363573 -1.679295 -1.957025 4.561485 10.518359 0.677451\n8388 21.590467 1.167798 -1.370604 -1.742090 4.486655 10.595284 0.574208\n8389 21.596521 1.047620 -1.216148 -1.614478 4.510725 10.559636 0.615127\n8390 21.602481 0.775338 -0.905232 -1.332251 4.715310 10.406419 0.763229\n8391 21.608597 0.630787 -0.748253 -1.184777 4.868891 10.471772 0.849925\n8392 21.614745 0.346567 -0.424358 -0.887409 5.147592 10.953508 0.892643\n8393 21.620735 0.216652 -0.253612 -0.740649 5.215791 11.265909 0.833292\n8394 21.626731 -0.009945 0.108002 -0.448520 5.001566 11.794878 0.497457\n8395 21.632734 -0.103533 0.296904 -0.303979 4.934487 12.003027 0.283224\n8396 21.638769 -0.248303 0.678948 -0.017637 4.987740 12.264368 0.118312\n8397 21.644864 -0.302126 0.867496 0.126141 5.016974 12.248104 0.154201\n8398 21.650847 -0.389728 1.226526 0.407706 5.028626 11.773201 0.315501\n8399 21.656880 -0.433476 1.392478 0.542661 4.938806 11.428480 0.375416\n8400 21.662985 -0.529861 1.691879 0.806868 4.638732 11.015168 0.446521\n8401 21.669041 -0.582886 1.828516 0.936079 4.450988 10.960004 0.528462\n8402 21.675091 -0.691122 2.083686 1.184825 3.984743 10.806665 0.876430\n8403 21.681439 -0.754498 2.230802 1.331252 3.757436 10.569062 1.148753\n8404 21.687249 -0.855155 2.439463 1.538412 3.655352 10.277203 1.620444\n8405 21.693204 -0.905354 2.528676 1.628796 3.685583 10.241974 1.784719\n8406 21.699144 -1.011983 2.680895 1.797351 3.811872 10.239119 2.093528\n8407 21.705156 -1.066436 2.743608 1.877280 3.840675 10.178645 2.273823\n8408 21.711319 -1.176790 2.849766 2.029132 3.866539 9.934952 2.565965\n8409 21.717255 -1.228767 2.894072 2.100824 3.952955 9.781559 2.681988\n8410 21.723438 -1.335160 2.970896 2.232301 4.299718 9.518605 2.814304\n8411 21.729499 -1.392643 3.006583 2.290529 4.523987 9.354861 2.774285\n8412 21.735505 -1.532954 3.078587 2.387223 4.790155 8.997968 2.801608\n8413 21.741569 -1.602876 3.116016 2.426456 4.667559 8.843882 2.936791\n8414 21.747630 -1.742547 3.217828 2.489012 4.204918 8.608400 3.253446\n8415 21.753580 -1.813050 3.278574 2.514416 3.967516 8.481995 3.330685\n8416 21.759682 -1.953202 3.413507 2.561881 3.588954 8.186934 3.284467\n8417 21.765750 -2.019146 3.488687 2.580786 3.474249 8.033710 3.361721\n8418 21.771778 -2.145373 3.643859 2.607791 3.216920 7.727211 3.670129\n8419 21.777729 -2.204102 3.722374 2.620992 3.099549 7.568694 3.788900\n8420 21.783935 -2.309806 3.878152 2.650018 2.957002 7.267228 4.062648\n8421 21.790450 -2.408208 4.020869 2.686880 2.823172 7.003058 4.346184\n8422 21.796064 -2.454961 4.086765 2.708621 2.753751 6.817382 4.509888\n8423 21.802426 -2.546455 4.200256 2.745405 2.583460 6.364559 4.987769\n8424 21.808148 -2.592234 4.246871 2.758312 2.491095 6.142652 5.232722\n8425 21.814762 -2.682160 4.319015 2.771569 2.434542 5.833743 5.687363\n8426 21.820102 -2.725098 4.343400 2.772635 2.425348 5.731763 5.879375\n8427 21.826578 -2.800731 4.371996 2.769600 2.283553 5.520090 6.188496\n8428 21.832304 -2.830452 4.377976 2.763959 2.161479 5.379131 6.383585\n8429 21.838652 -2.872684 4.375494 2.736455 2.044823 5.146669 6.715940\n8430 21.844223 -2.884766 4.368107 2.714312 2.077456 5.138816 6.840519\n8431 21.850627 -2.892344 4.342240 2.655345 2.122993 5.284769 6.997330\n8432 21.856360 -2.888776 4.324066 2.620281 2.031351 5.334306 7.021847\n8433 21.862497 -2.859645 4.280512 2.544106 1.614742 5.200639 6.945360\n8434 21.868432 -2.834052 4.254636 2.504492 1.356101 5.023035 6.944108\n8435 21.874625 -2.764205 4.193663 2.424311 0.927377 4.519966 7.163373\n8436 21.880689 -2.720398 4.160988 2.384524 0.771077 4.249753 7.400529\n8437 21.886702 -2.621958 4.093232 2.302922 0.541273 3.637433 8.028336\n8438 21.892434 -2.574162 4.058777 2.259352 0.467938 3.286210 8.326332\n8439 21.898699 -2.488266 3.987924 2.167203 0.429521 2.610541 8.815169\n8440 21.904722 -2.450584 3.948763 2.120242 0.475040 2.363843 8.931034\n8441 21.910729 -2.376343 3.862464 2.033513 0.556688 2.167724 8.928236\n8442 21.916809 -2.337950 3.814681 1.995654 0.522808 2.118797 8.867469\n8443 21.922791 -2.260575 3.711195 1.926512 0.281847 1.949402 8.735223\n8444 21.928890 -2.224548 3.657917 1.893282 0.083046 1.828308 8.711407\n8445 21.934821 -2.165865 3.552015 1.825397 -0.266282 1.535704 8.799579\n8446 21.940849 -2.146292 3.500931 1.790919 -0.355978 1.431834 8.866041\n8447 21.947108 -2.121737 3.405345 1.726349 -0.476238 1.395614 9.012789\n8448 21.952906 -2.112675 3.360882 1.696931 -0.581397 1.368005 9.094020\n8449 21.958972 -2.093513 3.282847 1.634180 -0.936496 1.178593 9.217483\n8450 21.964991 -2.085855 3.250085 1.596462 -1.156941 1.052395 9.175725\n8451 21.971202 -2.072609 3.189824 1.509035 -1.578229 0.819676 8.946470\n8452 21.977043 -2.068614 3.154343 1.451628 -1.783995 0.799112 8.818563\n8453 21.983188 -2.066370 3.098541 1.368692 -1.996302 0.902700 8.822920\n8454 21.989178 -2.067255 3.071452 1.333687 -2.022730 0.887780 8.893695\n8455 21.995222 -2.070132 3.018446 1.271777 -1.990035 0.758032 9.011291\n8456 22.001224 -2.072411 2.991208 1.242917 -1.992845 0.701199 9.010479\n8457 22.007396 -2.074014 2.936515 1.186561 -2.140088 0.570218 8.952808\n8458 22.013515 -2.072822 2.910711 1.159186 -2.290211 0.513293 8.920097\n8459 22.019481 -2.060755 2.864260 1.108632 -2.662883 0.436963 8.848144\n8460 22.025472 -2.047270 2.843836 1.087227 -2.832307 0.355978 8.802016\n8461 22.031556 -2.003301 2.808439 1.048100 -3.061110 0.008380 8.764547\n8462 22.037614 -1.975777 2.792187 1.028465 -3.169968 -0.194025 8.743076\n8463 22.043610 -1.913325 2.760921 0.986174 -3.472564 -0.473021 8.672477\n8464 22.049572 -1.882256 2.746580 0.962569 -3.628384 -0.607027 8.642065\n8465 22.055659 -1.828832 2.722018 0.910378 -3.879073 -0.848834 8.644963\n8466 22.061673 -1.805734 2.711665 0.883483 -4.031872 -0.892178 8.680264\n8467 22.067755 -1.762025 2.694068 0.825531 -4.357113 -1.082950 8.818051\n8468 22.073724 -1.742434 2.685639 0.791759 -4.522092 -1.298761 8.926483\n8469 22.079982 -1.712710 2.660132 0.716738 -4.800720 -1.772748 9.108269\n8470 22.085851 -1.702062 2.640580 0.676403 -4.899439 -1.939452 9.165067\n8471 22.091965 -1.681693 2.584009 0.592735 -5.015782 -2.050603 9.275889\n8472 22.097985 -1.668623 2.547518 0.550394 -4.942791 -2.029923 9.324078\n8473 22.103998 -1.635104 2.459427 0.462972 -4.754508 -2.015467 9.339531\n8474 22.109999 -1.614626 2.406303 0.416394 -4.651453 -2.085070 9.284170\n8475 22.115929 -1.567711 2.288216 0.325630 -5.109950 -2.425676 9.227085\n8476 22.121994 -1.541599 2.225469 0.281276 -5.406143 -2.551440 9.246834\n8477 22.128160 -1.491243 2.091275 0.198106 -5.960320 -2.659337 9.412427\n8478 22.134237 -1.466741 2.019484 0.165029 -6.147852 -2.630600 9.550538\n8479 22.140185 -1.414604 1.865256 0.110214 -6.250548 -2.507020 9.807665\n8480 22.146478 -1.386166 1.782693 0.084405 -6.220426 -2.437617 9.898167\n8481 22.152395 -1.319396 1.602586 0.037062 -5.899848 -2.352156 9.940904\n8482 22.158516 -1.278190 1.506262 0.013586 -5.651527 -2.318534 9.924465\n8483 22.164301 -1.166903 1.305153 -0.032793 -5.118599 -2.167253 9.909441\n8484 22.170377 -1.086871 1.203009 -0.048457 -4.833379 -2.107582 9.761221\n8485 22.176500 -0.875068 1.012846 -0.079081 -4.618680 -2.196812 9.267061\n8486 22.182508 -0.770882 0.926211 -0.097749 -4.703765 -2.298696 9.178738\n8487 22.188500 -0.549281 0.781268 -0.155298 -4.968485 -2.517502 8.833755\n8488 22.194480 -0.439591 0.727608 -0.193701 -5.095860 -2.686037 8.757111\n8489 22.200691 -0.257950 0.637241 -0.284455 -5.500015 -3.122428 8.565086\n8490 22.206665 -0.189783 0.599997 -0.334260 -5.785948 -3.317634 8.449676\n8491 22.212805 -0.086032 0.535595 -0.438421 -6.356784 -3.667049 8.519257\n8492 22.219241 -0.032414 0.471144 -0.548478 -6.678027 -3.835409 8.581080\n8493 22.224783 -0.020393 0.437699 -0.602556 -6.742329 -3.832119 8.574421\n8494 22.231333 -0.023086 0.365446 -0.702973 -6.778169 -3.731477 8.622266\n8495 22.236934 -0.035136 0.328086 -0.747332 -6.775308 -3.603429 8.635570\n8496 22.243324 -0.056898 0.256075 -0.818547 -6.716824 -3.214723 8.657589\n8497 22.248985 -0.059235 0.221258 -0.845463 -6.681334 -3.029206 8.608726\n8498 22.255478 -0.039464 0.154808 -0.885494 -6.692101 -2.812298 8.459186\n8499 22.261074 -0.018267 0.122531 -0.900475 -6.730112 -2.781885 8.412808\n8500 22.267484 0.036149 0.059241 -0.927640 -6.848698 -2.760592 8.476173\n8501 22.273197 0.064812 0.027859 -0.942151 -6.917591 -2.733604 8.526941\n8502 22.279571 0.122550 -0.037823 -0.975632 -7.057560 -2.718512 8.553734\n8503 22.285199 0.150112 -0.075529 -0.995782 -7.105313 -2.751143 8.534550\n8504 22.291462 0.217772 -0.170158 -1.045805 -7.204512 -2.847731 8.599998\n8505 22.297329 0.261054 -0.227169 -1.075813 -7.244803 -2.922320 8.693748\n8506 22.303357 0.369496 -0.359320 -1.147462 -7.294504 -3.174732 8.872450\n8507 22.309407 0.431939 -0.435034 -1.188203 -7.314530 -3.313374 8.929129\n8508 22.315549 0.571540 -0.602879 -1.275325 -7.323972 -3.561185 9.076548\n8509 22.321529 0.647934 -0.693638 -1.320984 -7.320253 -3.685326 9.194039\n8510 22.327659 0.816608 -0.887393 -1.417809 -7.318048 -4.073088 9.406180\n8511 22.333599 0.910284 -0.988841 -1.470044 -7.330167 -4.337527 9.468226\n8512 22.339687 1.110414 -1.196494 -1.580584 -7.347468 -4.699246 9.527980\n8513 22.345815 1.214064 -1.299239 -1.636377 -7.360106 -4.731375 9.522918\n8514 22.351655 1.417409 -1.493773 -1.743145 -7.361594 -4.563893 9.501657\n8515 22.357806 1.514388 -1.585351 -1.794265 -7.340933 -4.405007 9.463266\n8516 22.363797 1.698423 -1.758947 -1.891267 -7.247129 -4.018869 9.354280\n8517 22.369924 1.792201 -1.841887 -1.935604 -7.197961 -3.832919 9.314103\n8518 22.375743 1.984889 -1.996425 -2.009624 -6.997394 -3.631544 9.247979\n8519 22.381962 2.081787 -2.068343 -2.035838 -6.843937 -3.602724 9.248422\n8520 22.388124 2.271677 -2.202047 -2.057620 -6.453138 -3.503543 9.264668\n8521 22.393871 2.364221 -2.263114 -2.053031 -6.207581 -3.394320 9.316607\n8522 22.400275 2.537466 -2.374783 -2.015167 -5.735999 -3.100932 9.497159\n8523 22.406026 2.618616 -2.425237 -1.983466 -5.555201 -2.962657 9.562576\n8524 22.412269 2.776032 -2.512661 -1.903399 -5.313187 -2.736380 9.596577\n8525 22.418001 2.854249 -2.549982 -1.856237 -5.214166 -2.607076 9.529745\n8526 22.424150 3.009721 -2.613559 -1.746640 -4.966035 -2.380350 9.394279\n8527 22.430122 3.085025 -2.639887 -1.684762 -4.822936 -2.303034 9.363561\n8528 22.436225 3.227472 -2.681742 -1.552247 -4.542248 -2.045706 9.362412\n8529 22.442098 3.293901 -2.697948 -1.484911 -4.414508 -1.830426 9.365604\n8530 22.448184 3.415266 -2.724090 -1.358560 -4.233304 -1.362522 9.326403\n8531 22.454238 3.468711 -2.736952 -1.303289 -4.159145 -1.153691 9.288347\n8532 22.460325 3.550479 -2.773156 -1.214980 -3.934168 -0.800070 9.240999\n8533 22.466525 3.575341 -2.800455 -1.182099 -3.775630 -0.668331 9.268178\n8534 22.472422 3.591196 -2.875805 -1.137212 -3.373995 -0.469035 9.440137\n8535 22.478643 3.579954 -2.923737 -1.124242 -3.167039 -0.370546 9.540193\n8536 22.484435 3.519592 -3.037068 -1.121385 -2.808166 -0.259906 9.653357\n8537 22.490405 3.469780 -3.102024 -1.135248 -2.670671 -0.305317 9.691395\n8538 22.496569 3.341324 -3.245094 -1.199938 -2.388922 -0.535691 9.773128\n8539 22.502704 3.270202 -3.319199 -1.249370 -2.201594 -0.565582 9.752564\n8540 22.508701 3.125598 -3.465521 -1.368335 -1.764541 -0.322209 9.495494\n8541 22.514672 3.054725 -3.536751 -1.432644 -1.527118 -0.135220 9.297858\n8542 22.520746 2.923699 -3.665940 -1.563725 -1.031172 0.397541 8.998637\n8543 22.526849 2.867855 -3.718786 -1.628548 -0.776466 0.779958 8.886655\n8544 22.532922 2.777894 -3.796350 -1.752689 -0.326214 1.673702 8.566260\n8545 22.538784 2.742624 -3.819180 -1.810124 -0.159927 2.085592 8.364517\n8546 22.545098 2.690373 -3.830932 -1.910785 0.022341 2.630727 7.968123\n8547 22.550922 2.671750 -3.819218 -1.951780 0.090064 2.787630 7.825708\n8548 22.556892 2.650305 -3.762042 -2.011405 0.292831 2.993537 7.594293\n8549 22.563169 2.646583 -3.717889 -2.030439 0.427641 3.042755 7.502108\n8550 22.569055 2.648833 -3.607687 -2.055334 0.607042 2.974942 7.435281\n8551 22.575135 2.653668 -3.543433 -2.067063 0.630595 2.879998 7.485486\n8552 22.581180 2.672205 -3.398187 -2.095486 0.711418 2.835051 7.659916\n8553 22.587313 2.684063 -3.318953 -2.109210 0.810730 3.016912 7.652723\n8554 22.593236 2.716510 -3.156526 -2.123956 1.011032 3.746689 7.449134\n8555 22.599275 2.737821 -3.075413 -2.121936 1.036965 4.149320 7.322886\n8556 22.605155 2.792681 -2.917488 -2.101920 0.966974 4.664287 7.129824\n8557 22.611484 2.822785 -2.842623 -2.085910 0.939893 4.782649 7.042669\n8558 22.617466 2.883585 -2.706301 -2.036008 1.014840 5.035349 6.828723\n8559 22.623542 2.910010 -2.646574 -1.996942 1.110773 5.183128 6.766479\n8560 22.629383 2.943317 -2.545105 -1.880627 1.374147 5.326027 6.848365\n8561 22.635547 2.950823 -2.503280 -1.804519 1.509701 5.283266 6.963558\n8562 22.641558 2.949347 -2.440780 -1.627105 1.830503 4.991271 7.266553\n8563 22.647561 2.940968 -2.421080 -1.531419 2.004056 4.843297 7.418209\n8564 22.653795 2.909642 -2.400813 -1.339526 2.204573 4.731077 7.577749\n8565 22.659680 2.889818 -2.401040 -1.248400 2.223044 4.742097 7.579505\n8566 22.665782 2.845529 -2.424034 -1.090435 2.316326 4.840309 7.372674\n8567 22.671700 2.828975 -2.454539 -1.010910 2.512006 5.139530 7.235504\n8568 22.677900 2.820423 -2.508265 -0.922853 2.830316 5.872765 6.905293\n8569 22.683846 2.825416 -2.542924 -0.885231 2.946259 6.311984 6.685179\n8570 22.689763 2.853071 -2.616619 -0.832119 3.054910 7.019915 6.213747\n8571 22.695883 2.869772 -2.637671 -0.817640 3.037143 7.255670 5.989019\n8572 22.701760 2.902717 -2.650816 -0.784112 2.923445 7.759649 5.507460\n8573 22.708481 2.927174 -2.627445 -0.717247 2.679516 8.218678 4.919339\n8574 22.714101 2.934978 -2.606071 -0.666984 2.565009 8.302877 4.710389\n8575 22.720424 2.932900 -2.584970 -0.608009 2.499926 8.260755 4.558165\n8576 22.726066 2.896220 -2.552042 -0.479756 2.529499 8.038517 4.502038\n8577 22.732555 2.858944 -2.540034 -0.416143 2.542649 7.954425 4.540132\n8578 22.738125 2.736430 -2.527319 -0.298291 2.611255 7.793845 4.754618\n8579 22.744939 2.540389 -2.529173 -0.196056 2.708923 7.522166 4.754892\n8580 22.750280 2.424233 -2.538364 -0.151002 2.759902 7.344594 4.775008\n8581 22.756577 2.172931 -2.581239 -0.076102 2.750286 7.043963 4.863923\n8582 22.762446 2.053491 -2.613935 -0.045814 2.690064 7.025167 4.955771\n8583 22.768903 1.841642 -2.697640 0.004469 2.671790 7.238764 5.027866\n8584 22.774465 1.757187 -2.747020 0.026626 2.706703 7.426263 4.956160\n8585 22.780766 1.631494 -2.845889 0.068907 2.817181 7.817737 4.606819\n8586 22.786466 1.592353 -2.893287 0.089174 2.953408 7.998008 4.381860\n8587 22.792735 1.566035 -2.982189 0.130603 3.331278 8.270265 3.980271\n8588 22.798523 1.577824 -3.022677 0.152384 3.569883 8.344826 3.826594\n8589 22.804832 1.643934 -3.096274 0.192228 4.144971 8.319355 3.546016\n8590 22.810813 1.685633 -3.129074 0.209951 4.401119 8.253400 3.365256\n8591 22.816785 1.739364 -3.182247 0.242201 4.815950 8.188236 2.997358\n8592 22.822647 1.753324 -3.200884 0.253354 4.914646 8.266748 2.764972\n8593 22.828891 1.767539 -3.221451 0.264628 4.859147 8.595031 2.334046\n8594 22.834876 1.765959 -3.225536 0.264931 4.854090 8.738797 2.207168\n8595 22.840908 1.745062 -3.224060 0.253115 5.031210 8.783176 2.026219\n8596 22.846713 1.734210 -3.218755 0.242562 5.161462 8.717874 1.957238\n8597 22.852941 1.705426 -3.201392 0.218712 5.389103 8.524956 1.798893\n8598 22.858855 1.675603 -3.186557 0.206422 5.407539 8.402749 1.707955\n8599 22.864978 1.594136 -3.139462 0.188240 5.157615 8.179768 1.564001\n8600 22.871012 1.546136 -3.106245 0.183085 5.015248 8.048496 1.473341\n8601 22.877236 1.454603 -3.017854 0.176661 4.926146 7.800769 1.255092\n8602 22.883213 1.419183 -2.962738 0.177849 4.954087 7.799121 1.136461\n8603 22.889047 1.365292 -2.825426 0.195895 5.157036 7.892367 0.842122\n8604 22.895263 1.344882 -2.739623 0.212937 5.279255 7.875153 0.689589\n8605 22.901113 1.313079 -2.531599 0.271232 5.564733 7.747820 0.314960\n8606 22.907305 1.298528 -2.409781 0.312102 5.720270 7.704823 0.101420\n8607 22.913239 1.285279 -2.134868 0.416251 5.945480 7.721105 -0.366702\n8608 22.919233 1.282644 -1.981745 0.479944 5.960747 7.759366 -0.563545\n8609 22.925487 1.297081 -1.646767 0.622031 5.789819 7.848996 -0.881515\n8610 22.931302 1.303316 -1.466656 0.696795 5.673283 7.895878 -0.972990\n8611 22.937449 1.311967 -1.089209 0.848647 5.479764 7.947895 -1.298584\n8612 22.943520 1.307069 -0.894076 0.925278 5.402172 8.004856 -1.377705\n8613 22.949609 1.277433 -0.499902 1.072805 5.458288 8.082771 -1.396776\n8614 22.955514 1.255876 -0.304115 1.142495 5.574386 8.093556 -1.337383\n8615 22.961532 1.206049 0.068703 1.272706 5.927972 8.035894 -1.162949\n8616 22.967513 1.179328 0.241141 1.331549 6.143191 7.945993 -1.101899\n8617 22.973758 1.119242 0.559670 1.440494 6.621374 7.860890 -1.065853\n8618 22.979783 1.085565 0.707000 1.491758 6.816714 7.945401 -1.092148\n8619 22.985761 1.011411 0.982110 1.587967 6.967678 8.226221 -1.152571\n8620 22.991760 0.973689 1.109403 1.633401 6.951713 8.281199 -1.164968\n8621 22.997760 0.903368 1.335095 1.721595 7.016264 8.103634 -1.125402\n8622 23.003920 0.872827 1.431120 1.765417 7.156320 7.967647 -1.048447\n8623 23.009972 0.821449 1.588460 1.855951 7.517058 7.670256 -0.798912\n8624 23.016037 0.802236 1.650166 1.903993 7.646631 7.515399 -0.733584\n8625 23.021809 0.791301 1.746199 2.003236 7.688357 7.388041 -0.686611\n8626 23.027995 0.796287 1.782311 2.051435 7.645426 7.408033 -0.587158\n8627 23.033895 0.824371 1.833386 2.135200 7.598622 7.355503 -0.315244\n8628 23.039956 0.849120 1.848035 2.167940 7.649695 7.256060 -0.173083\n8629 23.046169 0.915775 1.854719 2.216856 7.902481 7.003452 0.070887\n8630 23.052056 0.954256 1.848902 2.236025 8.027039 6.901399 0.201720\n8631 23.058134 1.034699 1.826393 2.268784 8.131735 6.663537 0.433785\n8632 23.064220 1.076181 1.812987 2.282192 8.096149 6.483872 0.481180\n8633 23.070464 1.161006 1.789572 2.301687 7.988720 6.091228 0.540396\n8634 23.077024 1.242379 1.776095 2.308333 7.898734 5.909964 0.637305\n8635 23.082470 1.279141 1.775398 2.307490 7.822999 5.916118 0.633199\n8636 23.088470 1.314098 1.778823 2.305677 7.703452 5.939907 0.570691\n8637 23.094499 1.378250 1.795640 2.304563 7.407395 5.933597 0.406172\n8638 23.100865 1.438807 1.816454 2.312495 7.350747 5.910117 0.281482\n8639 23.106608 1.472609 1.824970 2.320429 7.456419 5.932482 0.311631\n8640 23.113007 1.536174 1.832851 2.342669 7.791846 5.981277 0.534342\n8641 23.118536 1.561532 1.832091 2.355019 7.953980 5.966567 0.626473\n8642 23.124957 1.588281 1.819763 2.378745 8.218946 5.885946 0.694542\n8643 23.130592 1.589763 1.808150 2.389580 8.318528 5.771156 0.678554\n8644 23.137128 1.582247 1.776255 2.414438 8.503875 5.386233 0.688344\n8645 23.142959 1.579024 1.756159 2.430301 8.583664 5.236394 0.754030\n8646 23.149099 1.580946 1.710220 2.470871 8.701900 5.129435 0.985100\n8647 23.154850 1.585040 1.685059 2.493930 8.765006 5.117192 1.106673\n8648 23.160929 1.581905 1.629414 2.536545 8.861843 4.999643 1.328075\n8649 23.167052 1.569657 1.597025 2.552613 8.905901 4.931682 1.377783\n8650 23.173001 1.526454 1.524484 2.570745 8.960973 4.920955 1.391347\n8651 23.178875 1.499221 1.484466 2.573997 8.971008 4.913178 1.388754\n8652 23.185081 1.444792 1.395248 2.573020 9.070262 4.683658 1.421052\n8653 23.191011 1.417922 1.346398 2.569695 9.158967 4.516057 1.465374\n8654 23.197165 1.360255 1.241787 2.556206 9.293210 4.245470 1.440443\n8655 23.203129 1.324171 1.187812 2.544950 9.313025 4.167037 1.430300\n8656 23.209351 1.231518 1.080846 2.512833 9.307083 4.066580 1.421553\n8657 23.215220 1.180856 1.028976 2.494016 9.298452 4.002526 1.407654\n8658 23.221261 1.093360 0.922523 2.456144 9.323318 3.839962 1.462951\n8659 23.227261 1.063961 0.865631 2.439558 9.364639 3.781719 1.499281\n8660 23.233438 1.037195 0.749488 2.416659 9.413142 3.728392 1.559664\n8661 23.239324 1.035024 0.692609 2.408703 9.415324 3.728015 1.549800\n8662 23.245491 1.037444 0.589135 2.386168 9.309817 3.745238 1.421916\n8663 23.251481 1.038083 0.543961 2.367806 9.233554 3.684402 1.376469\n8664 23.257552 1.032755 0.470350 2.313365 9.124367 3.379058 1.446974\n8665 23.263522 1.025409 0.445697 2.278355 9.079383 3.161081 1.512490\n8666 23.269497 0.998712 0.424939 2.196921 9.040543 2.592263 1.615548\n8667 23.275751 0.975192 0.429015 2.152462 9.069656 2.294366 1.635313\n8668 23.281652 0.898539 0.467617 2.061944 9.118189 1.775710 1.740140\n8669 23.287872 0.841845 0.499269 2.016017 9.070869 1.581977 1.812163\n8670 23.293876 0.706964 0.573042 1.923362 8.993755 1.392180 1.753077\n8671 23.299716 0.636459 0.610952 1.877642 9.033073 1.393700 1.703160\n8672 23.305816 0.511723 0.691422 1.792138 9.173185 1.572127 1.563791\n8673 23.311835 0.463570 0.739413 1.752583 9.219974 1.708757 1.439821\n8674 23.317931 0.408230 0.853424 1.677275 9.377832 1.870599 1.002965\n8675 23.323825 0.397118 0.919135 1.640164 9.545315 1.915540 0.817665\n8676 23.329801 0.403781 1.065119 1.561518 9.930746 2.007156 0.676073\n8677 23.335837 0.420055 1.144140 1.517077 10.082051 2.008337 0.708859\n8678 23.342162 0.478704 1.331019 1.402491 10.286731 1.904590 0.880532\n8679 23.348133 0.509161 1.415149 1.346759 10.349551 1.820000 0.974916\n8680 23.354147 0.568803 1.580395 1.230956 10.467117 1.463941 1.210525\n8681 23.360149 0.596448 1.659963 1.172300 10.520085 1.168329 1.382404\n8682 23.366256 0.646475 1.814085 1.056648 10.586817 0.568807 1.736536\n8683 23.372273 0.669236 1.887101 1.000301 10.574700 0.404195 1.844417\n8684 23.378550 0.710378 2.018226 0.891805 10.442126 0.238746 1.999785\n8685 23.384380 0.730204 2.075058 0.840251 10.358831 0.108189 2.079875\n8686 23.390506 0.772550 2.172872 0.744922 10.211958 -0.137866 2.265464\n8687 23.396666 0.798898 2.215449 0.703306 10.115153 -0.171968 2.384507\n8688 23.402493 0.868170 2.299726 0.635810 9.893437 -0.098920 2.669829\n8689 23.408671 0.908709 2.345743 0.609084 9.799184 -0.034048 2.806363\n8690 23.414419 0.992667 2.448713 0.563368 9.720348 0.078221 2.948581\n8691 23.420526 1.032138 2.503322 0.541201 9.731827 0.102505 2.983575\n8692 23.426654 1.097772 2.606780 0.491446 9.866811 0.123180 3.112365\n8693 23.432602 1.123512 2.650640 0.463833 9.950822 0.168182 3.222863\n8694 23.438734 1.163795 2.717343 0.407490 10.006388 0.287414 3.505401\n8695 23.444818 1.177894 2.738039 0.379664 9.959874 0.314035 3.672445\n8696 23.450689 1.193263 2.756355 0.323696 9.759644 0.433608 3.965893\n8697 23.456736 1.193228 2.758390 0.295879 9.615047 0.537943 4.095896\n8698 23.462846 1.173054 2.754543 0.239012 9.260231 0.629553 4.336683\n8699 23.469624 1.154912 2.749392 0.209362 9.082768 0.609680 4.445407\n8700 23.475219 1.111988 2.734586 0.150638 8.854809 0.568235 4.660463\n8701 23.480950 1.089410 2.725260 0.123948 8.792528 0.600683 4.764858\n8702 23.487022 1.045172 2.703903 0.078112 8.728718 0.780705 4.896875\n8703 23.493130 1.023968 2.693107 0.056184 8.704345 0.905899 4.936884\n8704 23.499744 0.973677 2.675735 0.003944 8.612047 1.075808 5.029669\n8705 23.505092 0.941224 2.670540 -0.028495 8.572574 1.064009 5.104462\n8706 23.511213 0.864605 2.667982 -0.104752 8.531482 0.989023 5.285902\n8707 23.517724 0.823946 2.669488 -0.145277 8.503396 0.973764 5.378020\n8708 23.523224 0.746317 2.671543 -0.221039 8.310892 0.966000 5.519947\n8709 23.529917 0.682234 2.661512 -0.283868 7.939564 0.948819 5.688344\n8710 23.535358 0.656479 2.648154 -0.310790 7.734040 0.971752 5.843247\n8711 23.541916 0.618123 2.601325 -0.360985 7.444912 1.099704 6.276481\n8712 23.547474 0.603689 2.566624 -0.386293 7.386701 1.145337 6.511043\n8713 23.553836 0.578087 2.473969 -0.441155 7.489211 1.189047 6.883835\n8714 23.559568 0.567416 2.415868 -0.470852 7.590427 1.234460 6.999490\n8715 23.565821 0.554465 2.281425 -0.531493 7.704764 1.333745 7.165473\n8716 23.571640 0.554507 2.209853 -0.562974 7.676676 1.331353 7.238503\n8717 23.577909 0.561564 2.070347 -0.633628 7.506490 1.247965 7.271016\n8718 23.583721 0.564435 2.005643 -0.674843 7.404973 1.240930 7.196048\n8719 23.590082 0.560234 1.894984 -0.771311 7.199658 1.402189 7.032139\n8720 23.595712 0.549711 1.851066 -0.826067 7.088772 1.541721 6.983185\n8721 23.602128 0.510412 1.787933 -0.942135 6.904502 1.781442 6.920704\n8722 23.608174 0.483942 1.767834 -1.000058 6.779781 1.829941 6.882772\n8723 23.614026 0.410558 1.743227 -1.112192 6.533407 1.790484 6.737077\n8724 23.619953 0.362267 1.734788 -1.166706 6.408732 1.733090 6.692255\n8725 23.625985 0.241684 1.716745 -1.272884 6.271626 1.635907 6.772787\n8726 23.631919 0.171290 1.710822 -1.328133 6.286873 1.627713 6.898130\n8727 23.637923 0.017552 1.706830 -1.446898 6.309523 1.714721 7.130737\n8728 23.644003 -0.059946 1.707404 -1.509853 6.265630 1.788690 7.224008\n8729 23.650259 -0.204247 1.709667 -1.638279 5.999077 2.038655 7.403116\n8730 23.656094 -0.266761 1.710198 -1.701516 5.784407 2.199278 7.492402\n8731 23.662252 -0.362658 1.701705 -1.821690 5.324056 2.379564 7.603715\n8732 23.668260 -0.397047 1.685476 -1.879187 5.140648 2.370042 7.638585\n8733 23.674463 -0.448874 1.618195 -1.984502 4.867335 2.352089 7.733471\n8734 23.680338 -0.469978 1.565081 -2.029550 4.807694 2.403760 7.853137\n8735 23.686498 -0.507372 1.416627 -2.102154 4.883236 2.611844 8.317596\n8736 23.692408 -0.526198 1.291211 -2.138334 5.034703 2.680201 8.667621\n8737 23.698429 -0.546533 1.037737 -2.192045 5.230419 2.648651 9.001594\n8738 23.704808 -0.554455 0.887965 -2.220620 5.252482 2.590247 9.041896\n8739 23.710453 -0.570168 0.553228 -2.283674 5.166343 2.475598 9.079313\n8740 23.716399 -0.574664 0.378539 -2.315340 5.065085 2.460423 9.109370\n8741 23.722434 -0.570195 0.032049 -2.372928 4.717272 2.446483 9.210313\n8742 23.728552 -0.565826 -0.137738 -2.398091 4.481086 2.398978 9.273394\n8743 23.734681 -0.561708 -0.464531 -2.441310 4.001339 2.226505 9.442915\n8744 23.740952 -0.565037 -0.619882 -2.458833 3.803164 2.109355 9.542565\n8745 23.746688 -0.589040 -0.915525 -2.483504 3.549412 1.947574 9.740626\n8746 23.752790 -0.607401 -1.054535 -2.489573 3.516249 1.944839 9.836299\n8747 23.758807 -0.648494 -1.309494 -2.484454 3.532740 2.022966 9.980476\n8748 23.764799 -0.671592 -1.424524 -2.474586 3.523134 2.064802 9.962362\n8749 23.770839 -0.723391 -1.633046 -2.448173 3.477791 2.174198 9.692838\n8750 23.776815 -0.750023 -1.729101 -2.433767 3.471196 2.244526 9.507570\n8751 23.782937 -0.800287 -1.911834 -2.405056 3.504861 2.487107 9.234155\n8752 23.788938 -0.825855 -2.000385 -2.390414 3.540448 2.643417 9.157567\n8753 23.794931 -0.882287 -2.176847 -2.356550 3.632423 2.884457 9.051830\n8754 23.801066 -0.915224 -2.265397 -2.336665 3.685040 2.982049 9.028938\n8755 23.807444 -0.998777 -2.438511 -2.296104 3.703469 3.234360 9.002805\n8756 23.813073 -1.050238 -2.522102 -2.278536 3.672570 3.362393 8.989381\n8757 23.819129 -1.172712 -2.683267 -2.255338 3.622810 3.505218 8.946235\n8758 23.824973 -1.240774 -2.763556 -2.251180 3.638251 3.554178 8.899632\n8759 23.831408 -1.386057 -2.927959 -2.254138 3.754740 3.700200 8.705327\n8760 23.837132 -1.461489 -3.012309 -2.258325 3.843921 3.766388 8.585360\n8761 23.843445 -1.607595 -3.178325 -2.268301 4.203645 3.874674 8.412252\n8762 23.849333 -1.677605 -3.254680 -2.274387 4.389118 3.923287 8.316715\n8763 23.855460 -1.806363 -3.381576 -2.294993 4.786285 3.956328 7.966642\n8764 23.861403 -1.863181 -3.429120 -2.311076 4.970835 3.919868 7.717383\n8765 23.867389 -1.952776 -3.491460 -2.348745 5.260983 3.759429 7.301477\n8766 23.873638 -1.983337 -3.506467 -2.367103 5.376461 3.667175 7.179522\n8767 23.879567 -2.021094 -3.511569 -2.395291 5.449702 3.603081 7.006173\n8768 23.885568 -2.035602 -3.507214 -2.402280 5.421752 3.624824 6.869814\n8769 23.891692 -2.061780 -3.500272 -2.404373 5.401821 3.641695 6.687706\n8770 23.897699 -2.077864 -3.500867 -2.402174 5.436036 3.594501 6.717442\n8771 23.903684 -2.111500 -3.513798 -2.394671 5.584799 3.514159 6.928349\n8772 23.910854 -2.139633 -3.534145 -2.377184 5.672773 3.655076 7.042189\n8773 23.917037 -2.148894 -3.541700 -2.360016 5.628968 3.715452 7.009969\n8774 23.922870 -2.171721 -3.544934 -2.301548 5.398082 3.648837 6.772820\n8775 23.929049 -2.182792 -3.541250 -2.261276 5.322289 3.626995 6.591229\n8776 23.934943 -2.195506 -3.525725 -2.162990 5.514466 3.882184 6.325178\n8777 23.940962 -2.191391 -3.513789 -2.103927 5.784744 4.185462 6.176538\n8778 23.947069 -2.149861 -3.473506 -1.971555 6.324250 4.878312 5.836035\n8779 23.953046 -2.113248 -3.442289 -1.902363 6.459671 5.162858 5.614254\n8780 23.959059 -2.017358 -3.353602 -1.767926 6.457362 5.570385 5.070910\n8781 23.965119 -1.962456 -3.295835 -1.702924 6.361656 5.677095 4.840918\n8782 23.971150 -1.850970 -3.161095 -1.585286 6.247000 5.695351 4.440248\n8783 23.977176 -1.795514 -3.090931 -1.536187 6.284237 5.576977 4.289411\n8784 23.983241 -1.690189 -2.960321 -1.467454 6.601943 5.036715 4.201232\n8785 23.989239 -1.642518 -2.902460 -1.450170 6.848410 4.635695 4.234596\n8786 23.995490 -1.561030 -2.803165 -1.448791 7.444249 3.801469 4.165051\n8787 24.001393 -1.526514 -2.759017 -1.460125 7.777143 3.474268 4.107252\n8788 24.007433 -1.476063 -2.668796 -1.500973 8.310555 3.185695 4.060280\n8789 24.013431 -1.458582 -2.618660 -1.529561 8.407389 3.288824 4.004050\n8790 24.019520 -1.425092 -2.507864 -1.599943 8.305612 3.711602 3.716366\n8791 24.025668 -1.403045 -2.448042 -1.640360 8.201085 3.917370 3.587409\n8792 24.031518 -1.345718 -2.322287 -1.722522 7.961153 4.188284 3.504679\n8793 24.037495 -1.309443 -2.258005 -1.758414 7.795588 4.299539 3.499005\n8794 24.043613 -1.228287 -2.131552 -1.806604 7.396694 4.502319 3.576350\n8795 24.049692 -1.180470 -2.056408 -1.816917 7.143476 4.607388 3.733821\n8796 24.055674 -1.119088 -1.949436 -1.807465 6.813772 4.877460 4.014280\n8797 24.061809 -1.096810 -1.907586 -1.798708 6.670461 5.120037 4.156209\n8798 24.067934 -1.064503 -1.857027 -1.789025 6.387514 5.586840 4.441646\n8799 24.073784 -1.045670 -1.847632 -1.790654 6.261821 5.603901 4.548914\n8800 24.079893 -1.002850 -1.859610 -1.806444 6.187722 5.196102 4.823332\n8801 24.085896 -0.982700 -1.880585 -1.817996 6.243703 4.973731 4.921010\n8802 24.092072 -0.946301 -1.947038 -1.834727 6.440398 4.804291 4.917696\n8803 24.097984 -0.931881 -1.993483 -1.835305 6.566457 4.827518 4.813561\n8804 24.104119 -0.908979 -2.117187 -1.820454 6.981252 4.909852 4.434771\n8805 24.110008 -0.893357 -2.192397 -1.808242 7.257178 4.991181 4.250129\n8806 24.116041 -0.840564 -2.351692 -1.776262 7.607698 5.312570 3.963544\n8807 24.122193 -0.804417 -2.426822 -1.753077 7.574764 5.556379 3.776155\n8808 24.128142 -0.727121 -2.548132 -1.680027 7.182142 6.047716 3.183094\n8809 24.134428 -0.695276 -2.590604 -1.627882 6.989571 6.160975 2.907664\n8810 24.140452 -0.654498 -2.644901 -1.501094 6.857521 6.067663 2.750897\n8811 24.146473 -0.640853 -2.659142 -1.432497 6.882972 5.940720 2.800797\n8812 24.152477 -0.607020 -2.671370 -1.295681 6.934087 5.804831 2.990766\n8813 24.158399 -0.586182 -2.674919 -1.230708 6.888011 5.804586 3.033394\n8814 24.164467 -0.538934 -2.681064 -1.112363 6.698684 5.909342 2.913764\n8815 24.170472 -0.517245 -2.684663 -1.058901 6.594505 6.012774 2.810669\n8816 24.176574 -0.485428 -2.697246 -0.955905 6.324863 6.261087 2.624564\n8817 24.182553 -0.476207 -2.708632 -0.904388 6.179171 6.341891 2.556918\n8818 24.188732 -0.469195 -2.750868 -0.802056 6.087628 6.238118 2.449970\n8819 24.195318 -0.459253 -2.828400 -0.701549 6.417025 5.825100 2.452382\n8820 24.200873 -0.452453 -2.875323 -0.651873 6.665067 5.621908 2.390509\n8821 24.207171 -0.445734 -2.973693 -0.552653 7.095988 5.452075 2.035242\n8822 24.212898 -0.446430 -3.020421 -0.504438 7.214078 5.507700 1.809861\n8823 24.219248 -0.459219 -3.092646 -0.424967 7.419957 5.714801 1.304962\n8824 24.224853 -0.468720 -3.115085 -0.399105 7.520419 5.766955 1.152921\n8825 24.231149 -0.493233 -3.138146 -0.376871 7.598668 5.728304 0.952755\n8826 24.236920 -0.504494 -3.139941 -0.377372 7.496194 5.693743 0.842456\n8827 24.243252 -0.535344 -3.139089 -0.382887 7.104756 5.681677 0.663819\n8828 24.248940 -0.561869 -3.140359 -0.380508 6.946929 5.680532 0.549926\n8829 24.255162 -0.629628 -3.150132 -0.362582 6.847810 5.728563 0.455015\n8830 24.261185 -0.666472 -3.160396 -0.351763 6.866499 5.775287 0.500802\n8831 24.267312 -0.727730 -3.186285 -0.339557 7.003555 5.790811 0.478119\n8832 24.273194 -0.745638 -3.199246 -0.340219 7.121081 5.798421 0.370051\n8833 24.279197 -0.750538 -3.218755 -0.348214 7.334172 5.994275 -0.042046\n8834 24.285100 -0.733252 -3.220125 -0.350415 7.382889 6.140726 -0.281471\n8835 24.291334 -0.661398 -3.200108 -0.343200 7.315979 6.336547 -0.634127\n8836 24.297305 -0.608298 -3.179715 -0.332655 7.213340 6.341355 -0.792957\n8837 24.303430 -0.475748 -3.122840 -0.301647 7.065395 6.164573 -0.957316\n8838 24.309414 -0.402592 -3.088572 -0.283134 7.085999 6.013057 -0.964971\n8839 24.315470 -0.253178 -3.011852 -0.238204 7.287889 5.767736 -1.039047\n8840 24.321675 -0.181125 -2.969322 -0.210080 7.475995 5.701823 -1.133932\n8841 24.327728 -0.044854 -2.876199 -0.141389 7.853573 5.665503 -1.406786\n8842 24.333582 0.019604 -2.825556 -0.102121 7.951672 5.671451 -1.582919\n8843 24.339575 0.142003 -2.717745 -0.025777 7.974473 5.635951 -1.942880\n8844 24.345704 0.199199 -2.660380 0.008554 7.904986 5.657070 -2.138784\n8845 24.351754 0.308622 -2.535150 0.074693 7.625762 5.928493 -2.501927\n8846 24.357812 0.358786 -2.465609 0.110132 7.515452 6.098691 -2.639869\n8847 24.364010 0.450505 -2.312243 0.192899 7.403432 6.336446 -2.824557\n8848 24.369867 0.491083 -2.229736 0.241062 7.373803 6.362308 -2.912234\n8849 24.375934 0.562407 -2.061161 0.343425 7.292773 6.379688 -3.089199\n8850 24.381852 0.594729 -1.978727 0.393478 7.199748 6.446308 -3.196955\n8851 24.388073 0.649818 -1.824986 0.485289 7.176374 6.561971 -3.377021\n8852 24.394041 0.668387 -1.756337 0.525425 7.342141 6.549394 -3.462180\n8853 24.400033 0.684764 -1.639485 0.594311 7.893431 6.435891 -3.717453\n8854 24.406128 0.684766 -1.589627 0.623957 8.177616 6.348990 -3.845162\n8855 24.412087 0.669372 -1.497263 0.671256 8.551830 6.099167 -4.052757\n8856 24.418173 0.653792 -1.450193 0.688525 8.624924 5.964493 -4.139176\n8857 24.424150 0.620004 -1.347819 0.713580 8.594397 5.730559 -4.245450\n8858 24.430363 0.604333 -1.289500 0.722065 8.491546 5.611710 -4.241342\n8859 24.436274 0.575353 -1.158141 0.736731 8.135829 5.389135 -4.139432\n8860 24.442326 0.559472 -1.085266 0.745565 7.939322 5.302451 -4.072804\n8861 24.448308 0.527495 -0.930688 0.767224 7.644277 5.185880 -3.916299\n8862 24.454466 0.510370 -0.852950 0.779171 7.571749 5.140938 -3.853523\n8863 24.460544 0.477990 -0.706470 0.800239 7.596480 5.032093 -3.848714\n8864 24.466438 0.464431 -0.640054 0.808171 7.686147 4.968363 -3.879337\n8865 24.472557 0.445619 -0.522572 0.818618 7.972381 4.853483 -3.992768\n8866 24.478512 0.441001 -0.467495 0.821632 8.114621 4.828170 -4.071858\n8867 24.484471 0.434072 -0.355941 0.824832 8.333876 4.859011 -4.298821\n8868 24.490773 0.429390 -0.296728 0.826423 8.396427 4.890697 -4.421815\n8869 24.496765 0.419873 -0.165460 0.832889 8.393185 4.953019 -4.576792\n8870 24.502708 0.416991 -0.091821 0.837449 8.330045 4.991325 -4.620813\n8871 24.508786 0.419308 0.068131 0.846990 8.201216 5.090162 -4.696202\n8872 24.514783 0.427209 0.151725 0.851757 8.169702 5.144009 -4.743630\n8873 24.520886 0.458124 0.318064 0.860074 8.123182 5.234494 -4.830021\n8874 24.526936 0.479864 0.398369 0.862006 8.101477 5.236348 -4.866867\n8875 24.533101 0.534418 0.552956 0.858709 8.134582 5.153386 -4.890625\n8876 24.539034 0.564748 0.626827 0.852831 8.215161 5.124532 -4.873065\n8877 24.545043 0.639028 0.784577 0.828067 8.476574 5.103338 -4.867527\n8878 24.551508 0.711704 0.921184 0.791547 8.699616 5.054668 -4.850346\n8879 24.557180 0.747554 0.990910 0.770062 8.771245 5.006514 -4.824683\n8880 24.563596 0.810730 1.137739 0.726790 8.848459 4.898073 -4.779572\n8881 24.569215 0.833334 1.216181 0.705882 8.866625 4.848047 -4.822883\n8882 24.575641 0.855036 1.379352 0.665312 8.952703 4.763562 -4.934630\n8883 24.581189 0.855260 1.460581 0.645064 9.038753 4.747038 -4.932961\n8884 24.587800 0.835110 1.613932 0.601448 9.210220 4.638826 -4.901191\n8885 24.593521 0.817076 1.685942 0.576240 9.292573 4.543300 -4.876916\n8886 24.599801 0.764387 1.820360 0.520187 9.496189 4.223057 -4.839825\n8887 24.605507 0.732498 1.883702 0.490913 9.619345 4.060887 -4.813054\n8888 24.611729 0.649495 2.010592 0.437296 9.729477 3.817370 -4.766538\n8889 24.620082 0.603208 2.075692 0.414012 9.707904 3.752738 -4.697315\n8890 24.623692 0.503594 2.215447 0.375093 9.502175 3.728424 -4.499874\n8891 24.629545 0.454435 2.289589 0.359241 9.335436 3.775918 -4.394748\n8892 24.636012 0.361506 2.436385 0.336135 9.013454 3.991916 -4.215943\n8893 24.641672 0.319249 2.505288 0.329905 8.914051 4.154997 -4.119689\n8894 24.647975 0.243090 2.625585 0.330035 8.881950 4.552403 -3.915041\n8895 24.653756 0.207246 2.675267 0.335181 8.935217 4.712867 -3.823532\n8896 24.660003 0.139982 2.750064 0.347989 9.128076 4.769176 -3.596831\n8897 24.665831 0.110301 2.775226 0.354455 9.290612 4.672025 -3.423837\n8898 24.671947 0.059950 2.806682 0.364398 9.738809 4.382047 -3.044440\n8899 24.677940 0.039646 2.815499 0.367862 9.954040 4.255456 -2.901102\n8900 24.684238 0.015632 2.828960 0.373639 10.216718 4.028370 -2.705035\n8901 24.689995 0.013221 2.840099 0.374697 10.277689 3.907786 -2.619054\n8902 24.696047 0.030909 2.886937 0.369442 10.265892 3.782675 -2.565114\n8903 24.702049 0.054253 2.928100 0.362496 10.203753 3.856005 -2.624675\n8904 24.708100 0.129956 3.054629 0.339933 9.973703 4.238312 -2.862895\n8905 24.714139 0.183025 3.141473 0.324856 9.788527 4.447048 -2.967752\n8906 24.720129 0.311109 3.359028 0.289253 9.294650 4.751092 -3.032572\n8907 24.726459 0.385646 3.485701 0.267783 8.945984 4.835198 -3.092164\n8908 24.732325 0.530526 3.766803 0.223319 8.358287 4.869744 -2.991291\n8909 24.738483 0.594477 3.913683 0.202318 8.221502 4.794292 -2.763121\n8910 24.744539 0.693094 4.209709 0.169332 8.189176 4.543530 -1.988810\n8911 24.750487 0.725088 4.351740 0.156708 8.229350 4.384274 -1.476173\n8912 24.756492 0.743255 4.603676 0.139561 8.268826 3.903821 -0.530135\n8913 24.762635 0.729342 4.710705 0.136140 8.265922 3.615994 -0.130831\n8914 24.768719 0.660457 4.878546 0.140489 8.318676 3.215606 0.647315\n8915 24.774643 0.612382 4.938628 0.148071 8.325976 3.198246 0.939614\n8916 24.780763 0.511858 5.016279 0.174108 8.257701 3.471081 1.475178\n8917 24.786767 0.459897 5.035707 0.191046 8.194295 3.676972 1.738276\n8918 24.792864 0.362889 5.042422 0.228617 8.064066 4.111454 2.215452\n8919 24.798866 0.320377 5.029996 0.247531 8.040556 4.272663 2.444661\n8920 24.804870 0.246865 4.973076 0.282889 8.001354 4.426553 2.773000\n8921 24.810920 0.216709 4.929885 0.299925 7.961547 4.472243 2.896027\n8922 24.816919 0.177645 4.820320 0.333446 7.710107 4.628927 2.938418\n8923 24.823110 0.172241 4.756413 0.348071 7.501838 4.673966 2.978309\n8924 24.829027 0.186905 4.620360 0.364401 7.225178 4.511330 3.297218\n8925 24.835237 0.206196 4.553687 0.364467 7.255157 4.349765 3.579758\n8926 24.841081 0.255041 4.433210 0.349621 7.556469 4.033259 4.136422\n8927 24.847288 0.278881 4.379256 0.336329 7.740018 3.844491 4.371474\n8928 24.853207 0.313737 4.285521 0.306148 7.916080 3.444863 4.646192\n8929 24.859387 0.326449 4.246078 0.294035 7.860811 3.311336 4.740050\n8930 24.865129 0.341567 4.182650 0.278129 7.700788 3.207144 4.895606\n8931 24.871365 0.346699 4.158815 0.274664 7.611388 3.284933 4.987920\n8932 24.877221 0.339156 4.127840 0.278361 7.419184 3.617789 5.022961\n8933 24.883448 0.320150 4.121346 0.283953 7.255735 3.792877 4.961534\n8934 24.889592 0.238020 4.124783 0.300886 6.778504 4.119862 4.820285\n8935 24.895494 0.177281 4.131530 0.314063 6.527867 4.260757 4.787468\n8936 24.901644 0.037786 4.144145 0.349610 5.977956 4.459579 4.904487\n8937 24.907509 -0.032348 4.145364 0.371424 5.681164 4.444604 5.056480\n8938 24.913752 -0.166217 4.131907 0.419108 5.110067 4.133358 5.486389\n8939 24.919737 -0.231207 4.118740 0.442595 4.947922 3.926487 5.736493\n8940 24.925727 -0.356798 4.082464 0.491661 4.743645 3.708125 6.249869\n8941 24.931634 -0.419376 4.061898 0.518108 4.726311 3.637368 6.473075\n8942 24.937971 -0.533058 4.019638 0.569764 4.701728 3.465569 6.940760\n8943 24.944621 -0.579187 3.998991 0.595661 4.585106 3.423588 7.114024\n8944 24.949844 -0.632682 3.956981 0.649970 4.257874 3.394292 7.323437\n8945 24.956384 -0.627936 3.925521 0.694843 3.817330 3.445585 7.323867\n8946 24.961859 -0.615373 3.913071 0.719272 3.530090 3.463582 7.294857\n8947 24.968347 -0.601936 3.903009 0.743159 3.284344 3.471758 7.291065\n8948 24.974033 -0.570671 3.885625 0.785669 2.942037 3.504672 7.466326\n8949 24.980623 -0.536401 3.866549 0.829912 2.883149 3.386645 7.910435\n8950 24.986113 -0.518058 3.853565 0.852070 2.928760 3.243866 8.174866\n8951 24.992842 -0.484019 3.816320 0.901909 2.970230 2.933590 8.388026\n8952 24.998178 -0.473030 3.789623 0.932125 3.007668 2.827934 8.434903\n8953 25.004724 -0.473027 3.715719 0.999302 3.018594 2.776614 8.590661\n8954 25.010311 -0.485461 3.671150 1.034718 2.973615 2.830303 8.693687\n8955 25.016505 -0.531725 3.564760 1.100808 2.794850 3.008106 8.811523\n8956 25.022406 -0.567967 3.503452 1.127681 2.646773 3.098936 8.802242\n8957 25.028597 -0.658576 3.367862 1.167720 2.336983 3.258245 8.770867\n8958 25.034467 -0.710846 3.295679 1.181700 2.222651 3.324176 8.765587\n8959 25.040590 -0.827154 3.149102 1.197621 2.071554 3.304402 8.692277\n8960 25.046659 -0.889762 3.076582 1.198555 2.020129 3.198101 8.632722\n8961 25.052712 -1.015597 2.936780 1.185679 1.855843 3.003139 8.601804\n8962 25.058744 -1.073987 2.873246 1.171855 1.717245 2.938039 8.688468\n8963 25.064874 -1.175492 2.762612 1.129243 1.389137 2.795236 8.926848\n8964 25.070600 -1.218066 2.714359 1.101635 1.211896 2.721547 8.980326\n8965 25.076600 -1.298657 2.624572 1.037758 0.888649 2.349741 8.933621\n8966 25.082830 -1.339656 2.580703 1.002413 0.769106 2.057883 8.942470\n8967 25.088778 -1.416485 2.492443 0.925476 0.621372 1.473453 9.102730\n8968 25.094781 -1.450293 2.448095 0.883672 0.570523 1.225040 9.254121\n8969 25.100927 -1.509820 2.357979 0.790901 0.417522 0.784032 9.627465\n8970 25.107058 -1.534777 2.311809 0.738393 0.283106 0.601740 9.832706\n8971 25.113133 -1.581450 2.214929 0.616658 0.054399 0.521574 10.075638\n8972 25.119084 -1.602437 2.160261 0.547063 0.020466 0.595659 10.133101\n8973 25.125166 -1.636693 2.028749 0.392747 0.245395 0.656265 10.152436\n8974 25.131180 -1.647251 1.951106 0.309039 0.512907 0.582975 10.163925\n8975 25.137081 -1.657982 1.777311 0.133043 1.064244 0.318916 10.184564\n8976 25.143341 -1.660925 1.682540 0.043211 1.228329 0.181867 10.186102\n8977 25.149221 -1.675109 1.484626 -0.138074 1.320052 -0.115590 10.101173\n8978 25.155303 -1.693302 1.384164 -0.228648 1.204054 -0.298977 10.057795\n8979 25.161343 -1.761694 1.183088 -0.412609 0.829710 -0.776410 10.149237\n8980 25.167344 -1.809936 1.083275 -0.509923 0.615582 -0.995610 10.283982\n8981 25.173527 -1.915959 0.885837 -0.713272 0.215324 -1.274308 10.579291\n8982 25.179484 -1.968646 0.788274 -0.817054 0.123570 -1.329452 10.689301\n8983 25.185468 -2.069512 0.599300 -1.025923 0.209509 -1.314205 10.771875\n8984 25.191592 -2.114939 0.511258 -1.129780 0.293819 -1.268103 10.752199\n8985 25.197608 -2.181649 0.364213 -1.337637 0.253859 -1.112781 10.681841\n8986 25.203544 -2.195806 0.317000 -1.440641 0.077748 -1.034595 10.625705\n8987 25.209588 -2.184251 0.293005 -1.636679 -0.397276 -0.954690 10.418500\n8988 25.215662 -2.164443 0.311592 -1.727941 -0.595889 -0.884579 10.160244\n8989 25.221724 -2.101171 0.382618 -1.893630 -0.775148 -0.680656 9.703773\n8990 25.227686 -2.051657 0.424777 -1.967874 -0.780727 -0.733305 9.755713\n8991 25.233850 -1.927192 0.511547 -2.107253 -0.752504 -0.864653 10.080192\n8992 25.239847 -1.858620 0.549088 -2.176355 -0.796203 -0.814259 10.180438\n8993 25.245809 -1.717063 0.605167 -2.317970 -0.996698 -0.547239 10.170067\n8994 25.251967 -1.640936 0.622729 -2.394506 -1.096977 -0.416211 10.186958\n8995 25.258100 -1.492804 0.628436 -2.568648 -1.250146 -0.487296 10.201899\n8996 25.264013 -1.422550 0.613431 -2.665963 -1.254997 -0.807677 10.216001\n8997 25.269967 -1.286801 0.539368 -2.873566 -1.073156 -1.734310 10.486423\n8998 25.276133 -1.222278 0.480681 -2.977047 -1.003254 -2.113765 10.673722\n8999 25.282221 -1.121801 0.319275 -3.163703 -1.001088 -2.831414 10.945458\n9000 25.288093 -1.090944 0.209711 -3.247008 -1.020860 -3.301246 11.085916\n9001 25.294178 -1.060170 -0.077420 -3.403168 -0.987216 -4.246080 11.686070\n9002 25.300181 -1.049121 -0.253702 -3.476186 -0.960868 -4.491052 12.181143\n9003 25.306307 -1.007262 -0.650944 -3.605442 -0.873653 -4.454143 12.984855\n9004 25.312297 -0.965944 -0.860727 -3.660138 -0.741428 -4.310203 13.136985\n9005 25.318382 -0.836719 -1.277153 -3.747816 -0.269786 -4.166198 12.975735\n9006 25.324905 -0.640723 -1.653370 -3.823302 0.167305 -4.290804 12.523700\n9007 25.330552 -0.515855 -1.816785 -3.863888 0.303405 -4.446772 12.263692\n9008 25.336845 -0.223491 -2.080475 -3.951145 0.428773 -4.783437 11.724716\n9009 25.342477 -0.063159 -2.177055 -3.995609 0.394804 -4.768728 11.446610\n9010 25.348928 0.256814 -2.297163 -4.083130 0.033081 -4.316845 10.842812\n9011 25.354651 0.402966 -2.324617 -4.128207 -0.213835 -4.069884 10.523198\n9012 25.360861 0.645710 -2.332143 -4.232942 -0.605439 -3.718629 10.016155\n9013 25.366691 0.735354 -2.318750 -4.295153 -0.707770 -3.555506 9.839992\n9014 25.372962 0.839622 -2.279713 -4.431076 -0.785212 -3.113734 9.541439\n9015 25.378758 0.854947 -2.263359 -4.494936 -0.823312 -2.801438 9.365062\n9016 25.385089 0.825473 -2.253595 -4.591190 -0.835262 -2.117646 9.139503\n9017 25.390910 0.785873 -2.263410 -4.621701 -0.770979 -1.846102 9.147733\n9018 25.396920 0.664618 -2.314530 -4.660499 -0.665654 -1.367636 9.309197\n9019 25.402892 0.589835 -2.353003 -4.677392 -0.655884 -1.160218 9.372038\n9020 25.408895 0.432247 -2.444131 -4.715700 -0.613113 -0.874305 9.461273\n9021 25.414900 0.352981 -2.492441 -4.733549 -0.511060 -0.659246 9.511569\n9022 25.421004 0.202686 -2.585155 -4.749680 -0.000474 0.145782 9.446200\n9023 25.427080 0.137785 -2.630938 -4.743546 0.354950 0.581455 9.371743\n9024 25.433068 0.035842 -2.729507 -4.700861 1.130346 0.778600 9.369204\n9025 25.439160 0.000655 -2.783485 -4.669039 1.589513 0.523713 9.487112\n9026 25.445154 -0.034620 -2.895809 -4.587404 2.363586 0.205763 9.657617\n9027 25.451187 -0.038044 -2.947746 -4.531841 2.579402 0.336904 9.603175\n9028 25.457275 -0.021992 -3.020925 -4.381261 2.905640 0.896724 9.125059\n9029 25.463326 -0.001540 -3.037321 -4.287413 3.080737 1.191969 8.769552\n9030 25.469350 0.067828 -3.028691 -4.085008 3.539210 1.791231 8.201143\n9031 25.475464 0.116318 -3.005350 -3.989123 3.829430 2.022171 8.034889\n9032 25.481512 0.226789 -2.928326 -3.813807 4.243516 2.273170 7.805544\n9033 25.487413 0.278352 -2.879886 -3.725684 4.256620 2.293738 7.678458\n9034 25.493524 0.347583 -2.775511 -3.538253 4.145470 2.042879 7.557319\n9035 25.499472 0.360593 -2.723806 -3.439200 4.133164 1.888611 7.634352\n9036 25.505581 0.347885 -2.629809 -3.236850 4.280281 1.819188 7.857024\n9037 25.511561 0.326856 -2.590829 -3.144114 4.389046 1.859216 7.942053\n9038 25.517626 0.271904 -2.538883 -3.004305 4.598748 1.843839 8.053970\n9039 25.523939 0.244356 -2.527377 -2.962312 4.806090 1.769690 8.107748\n9040 25.529806 0.198599 -2.533183 -2.928368 5.496439 1.737280 8.097602\n9041 25.535824 0.181508 -2.547356 -2.927955 5.813672 1.842755 8.041348\n9042 25.541741 0.166930 -2.591541 -2.943281 6.132117 2.081827 8.010354\n9043 25.548054 0.168948 -2.621432 -2.961290 6.211618 2.082469 8.018976\n9044 25.553947 0.187292 -2.703422 -3.030680 6.350322 1.994222 7.934287\n9045 25.559981 0.197005 -2.760617 -3.081864 6.533698 1.959343 7.815093\n9046 25.565958 0.204454 -2.907462 -3.204295 7.248319 1.948493 7.316612\n9047 25.572080 0.194618 -2.994088 -3.264502 7.613710 2.021364 7.011969\n9048 25.578100 0.145441 -3.170905 -3.360352 8.190189 2.307595 6.477511\n9049 25.584294 0.106674 -3.246786 -3.396062 8.373670 2.436673 6.316628\n9050 25.590173 0.004463 -3.350207 -3.452355 8.390120 2.664778 6.020422\n9051 25.596111 -0.058516 -3.371153 -3.478685 8.254451 2.816903 5.831029\n9052 25.602170 -0.196180 -3.342434 -3.538064 7.880977 3.359339 5.412588\n9053 25.608227 -0.266220 -3.293587 -3.566283 7.670573 3.740954 5.201785\n9054 25.614410 -0.395052 -3.136652 -3.605150 7.248206 4.394630 4.946437\n9055 25.620388 -0.446422 -3.032848 -3.615621 7.023101 4.532076 4.853532\n9056 25.626347 -0.516635 -2.796432 -3.625044 6.655467 4.423918 4.751536\n9057 25.632486 -0.540640 -2.674702 -3.626776 6.546580 4.260346 4.729200\n9058 25.638457 -0.575624 -2.440107 -3.625015 6.348915 4.145946 4.834096\n9059 25.644610 -0.587098 -2.334383 -3.620065 6.237844 4.250191 4.980262\n9060 25.650625 -0.610070 -2.161465 -3.600979 6.091589 4.505557 5.078583\n9061 25.656701 -0.625258 -2.100607 -3.589032 6.109186 4.625884 5.061193\n9062 25.662600 -0.659459 -2.039684 -3.567363 6.364957 4.888679 5.143549\n9063 25.668707 -0.671720 -2.035364 -3.559172 6.613665 5.012609 5.247647\n9064 25.674730 -0.689393 -2.064250 -3.549622 7.263133 5.237185 5.397277\n9065 25.680797 -0.699073 -2.091446 -3.547998 7.545397 5.379443 5.325540\n9066 25.686756 -0.718774 -2.144038 -3.547292 7.798464 5.762167 4.979789\n9067 25.692912 -0.726970 -2.160384 -3.546304 7.743571 5.971495 4.822674\n9068 25.698917 -0.739933 -2.160651 -3.541911 7.322655 6.293328 4.503706\n9069 25.704952 -0.746571 -2.143586 -3.539929 7.047124 6.322861 4.409273\n9070 25.710972 -0.758299 -2.086260 -3.539124 6.592854 6.064098 4.371947\n9071 25.717105 -0.763463 -2.049462 -3.537902 6.443963 5.837109 4.382899\n9072 25.723240 -0.778604 -1.964503 -3.522845 6.171380 5.441007 4.468514\n9073 25.729036 -0.789495 -1.917002 -3.504306 5.992549 5.335138 4.515100\n9074 25.735237 -0.804486 -1.805258 -3.442188 5.650252 5.444796 4.641648\n9075 25.741209 -0.798082 -1.741854 -3.399860 5.526538 5.707447 4.688924\n9076 25.747170 -0.737411 -1.614536 -3.299391 5.321381 6.471233 4.619215\n9077 25.753132 -0.686446 -1.558374 -3.244343 5.277444 6.821354 4.552626\n9078 25.759275 -0.547910 -1.484548 -3.127342 5.371113 7.225986 4.585651\n9079 25.765911 -0.371751 -1.474869 -2.992178 5.680506 7.278522 4.809238\n9080 25.771487 -0.277065 -1.496014 -2.916378 5.860776 7.233562 4.947432\n9081 25.777975 -0.090326 -1.579710 -2.754490 6.005857 7.065240 5.076155\n9082 25.783437 -0.004572 -1.635509 -2.673762 5.933213 6.913290 5.079980\n9083 25.790022 0.137964 -1.759367 -2.529914 5.468743 6.565066 5.013522\n9084 25.795530 0.197358 -1.820483 -2.468106 5.132052 6.488470 4.977455\n9085 25.802000 0.305654 -1.930481 -2.357105 4.603002 6.508266 5.005298\n9086 25.807662 0.353128 -1.977676 -2.302178 4.463437 6.558914 4.987289\n9087 25.813999 0.432118 -2.059223 -2.181017 4.263822 6.768527 4.922395\n9088 25.819754 0.469025 -2.095705 -2.114613 4.138606 6.928640 4.973019\n9089 25.826185 0.549622 -2.161889 -1.979500 3.989762 7.158422 5.032592\n9090 25.831866 0.588735 -2.194338 -1.913341 4.014132 7.207139 4.940423\n9091 25.838048 0.665330 -2.278244 -1.769533 4.280613 7.462063 4.385615\n9092 25.844025 0.687229 -2.306148 -1.722917 4.360220 7.620538 4.144186\n9093 25.850005 0.732832 -2.362504 -1.595320 4.405173 8.031052 3.602707\n9094 25.856174 0.741830 -2.377449 -1.529794 4.347173 8.196488 3.323830\n9095 25.862024 0.728933 -2.372457 -1.398379 4.144148 8.519795 2.812216\n9096 25.868064 0.710789 -2.351973 -1.332211 4.069698 8.698694 2.650942\n9097 25.874097 0.638094 -2.264508 -1.181998 4.041394 8.977127 2.358717\n9098 25.880113 0.593470 -2.209472 -1.113784 4.058066 9.013727 2.209855\n9099 25.886363 0.497924 -2.076012 -0.969453 4.090225 9.047915 1.888134\n9100 25.892147 0.454370 -1.998385 -0.894793 4.062465 9.124215 1.753722\n9101 25.898259 0.398073 -1.824715 -0.746581 3.862506 9.421700 1.653971\n9102 25.904218 0.382834 -1.732206 -0.675625 3.827312 9.458181 1.664646\n9103 25.910443 0.373962 -1.555297 -0.552733 4.079745 9.234373 1.762116\n9104 25.916378 0.382249 -1.476858 -0.502780 4.311587 9.056879 1.883720\n9105 25.922504 0.408542 -1.340698 -0.422666 4.785324 8.582760 2.286570\n9106 25.928383 0.423247 -1.283379 -0.390741 4.940915 8.313023 2.458430\n9107 25.934463 0.454150 -1.188596 -0.336160 5.007341 7.850749 2.649534\n9108 25.940439 0.470383 -1.151148 -0.312899 4.890456 7.701221 2.678703\n9109 25.946515 0.500922 -1.095605 -0.278993 4.591154 7.593881 2.665537\n9110 25.952531 0.517330 -1.078821 -0.268661 4.499277 7.596605 2.694091\n9111 25.958507 0.548113 -1.064837 -0.258051 4.490953 7.627989 2.787760\n9112 25.964632 0.561381 -1.066729 -0.256931 4.533224 7.640421 2.831918\n9113 25.970647 0.575355 -1.087493 -0.251368 4.647040 7.612598 2.859408\n9114 25.976833 0.575941 -1.105087 -0.242144 4.723936 7.615434 2.790857\n9115 25.982727 0.572800 -1.152676 -0.210427 4.854026 7.721051 2.533282\n9116 25.988872 0.571535 -1.183604 -0.191674 4.904293 7.777079 2.398738\n9117 25.994749 0.576428 -1.257013 -0.161913 4.945825 7.868182 2.137318\n9118 26.000796 0.581356 -1.295940 -0.152043 4.934361 7.920535 1.996644\n9119 26.007091 0.593519 -1.362895 -0.136885 4.871822 8.047500 1.722156\n9120 26.012894 0.601337 -1.384745 -0.128404 4.835826 8.083697 1.579596\n9121 26.018891 0.617605 -1.398628 -0.104047 4.821739 8.014781 1.323789\n9122 26.024956 0.625290 -1.390568 -0.087814 4.877210 7.924776 1.192740\n9123 26.031266 0.649749 -1.348818 -0.046819 5.171131 7.921355 0.892798\n9124 26.037212 0.667814 -1.317182 -0.022331 5.373616 8.027574 0.698456\n9125 26.043244 0.707041 -1.235366 0.033930 5.738835 8.279890 0.248422\n9126 26.049144 0.724718 -1.183881 0.065565 5.870233 8.393175 -0.001808\n9127 26.055320 0.751519 -1.056592 0.134735 6.030642 8.628618 -0.533611\n9128 26.061245 0.758087 -0.981512 0.171211 6.089231 8.733178 -0.782377\n9129 26.067360 0.758700 -0.814074 0.244864 6.213601 8.898432 -1.203168\n9130 26.073245 0.753227 -0.724620 0.280319 6.276384 8.928684 -1.353001\n9131 26.079454 0.730621 -0.538315 0.344719 6.381664 8.815076 -1.533367\n9132 26.085461 0.714140 -0.441698 0.372749 6.454253 8.710038 -1.574824\n9133 26.091422 0.673690 -0.243167 0.421389 6.605796 8.563613 -1.604514\n9134 26.097677 0.650958 -0.141261 0.443569 6.677252 8.521801 -1.612780\n9135 26.103436 0.604401 0.065649 0.485815 6.798258 8.422629 -1.676498\n9136 26.109470 0.581203 0.169613 0.506067 6.836603 8.373395 -1.734200\n9137 26.115549 0.536831 0.372715 0.542677 6.866945 8.333126 -1.916210\n9138 26.121636 0.518118 0.471240 0.558135 6.881220 8.398100 -2.011575\n9139 26.128049 0.484968 0.660353 0.583302 6.912142 8.668908 -2.144053\n9140 26.133652 0.468811 0.751087 0.592978 6.951527 8.847639 -2.204227\n9141 26.139726 0.437163 0.927396 0.604768 7.031895 9.137694 -2.283050\n9142 26.145764 0.420010 1.014593 0.607231 7.065760 9.167243 -2.249024\n9143 26.151935 0.376118 1.188565 0.605484 6.979408 8.923361 -2.099247\n9144 26.158599 0.356933 1.278960 0.603244 6.827539 8.742576 -2.068766\n9145 26.163971 0.323081 1.468436 0.597967 6.508790 8.369254 -1.940679\n9146 26.170598 0.309987 1.568038 0.596046 6.416389 8.213780 -1.892147\n9147 26.176083 0.302159 1.775463 0.595996 6.387335 8.003196 -1.740686\n9148 26.182633 0.309387 1.883407 0.597963 6.406354 7.892716 -1.663682\n9149 26.188455 0.344704 2.107770 0.606141 6.479120 7.692524 -1.555438\n9150 26.194751 0.404197 2.344498 0.627168 6.616567 7.843613 -1.442503\n9151 26.200158 0.441910 2.467535 0.647032 6.655206 8.015380 -1.443574\n9152 26.206801 0.533996 2.720639 0.709552 6.462729 8.345114 -1.502044\n9153 26.212353 0.584100 2.847522 0.750441 6.258138 8.468943 -1.499467\n9154 26.218799 0.680454 3.091823 0.846253 5.890352 8.732229 -1.393675\n9155 26.224265 0.722547 3.205693 0.900841 5.825702 8.927699 -1.248586\n9156 26.230751 0.780114 3.409460 1.025751 5.900000 9.367164 -0.887785\n9157 26.236445 0.792507 3.497709 1.095259 5.894108 9.502034 -0.764746\n9158 26.242727 0.785494 3.653317 1.246692 5.845290 9.670015 -0.512999\n9159 26.248724 0.765149 3.723375 1.328333 5.832475 9.747426 -0.316614\n9160 26.255028 0.709893 3.867335 1.504584 5.692459 9.918204 -0.034608\n9161 26.260644 0.672339 3.966870 1.623709 5.498468 9.982042 0.129010\n9162 26.266859 0.599845 4.145875 1.820553 5.061552 9.937230 0.320284\n9163 26.272779 0.560137 4.246298 1.919104 4.833419 9.849916 0.403420\n9164 26.278904 0.481659 4.458202 2.110821 4.484981 9.549617 0.501909\n9165 26.284771 0.446376 4.563107 2.201821 4.349486 9.287684 0.427686\n9166 26.290989 0.385145 4.763849 2.371358 4.261086 8.654860 0.472728\n9167 26.296803 0.357878 4.855167 2.448145 4.340309 8.392194 0.635367\n9168 26.303061 0.314722 5.022437 2.582990 4.665977 8.036949 1.118436\n9169 26.308865 0.298095 5.096142 2.640071 4.898318 7.877466 1.523493\n9170 26.314985 0.262617 5.219644 2.729225 5.473736 7.453808 2.392513\n9171 26.320914 0.245594 5.269164 2.762117 5.754719 7.237397 2.786096\n9172 26.327068 0.223361 5.337212 2.818060 6.077347 6.951901 3.372660\n9173 26.333021 0.222966 5.354257 2.845905 6.077453 6.865493 3.533965\n9174 26.339215 0.255934 5.358567 2.909328 5.797730 6.889218 3.811535\n9175 26.345039 0.284579 5.346039 2.944637 5.600208 6.974747 3.963115\n9176 26.350993 0.366587 5.292358 3.015201 5.100723 7.187198 4.298232\n9177 26.357189 0.410863 5.252360 3.048128 4.811275 7.252283 4.537248\n9178 26.363233 0.483874 5.143471 3.112526 4.369729 7.105824 5.203104\n9179 26.369405 0.510603 5.072221 3.146812 4.298665 6.935489 5.529424\n9180 26.375528 0.550989 4.890503 3.226084 4.526210 6.635462 6.097176\n9181 26.381270 0.566610 4.777337 3.270156 4.798726 6.536482 6.290879\n9182 26.387530 0.602171 4.511878 3.358798 5.330016 6.426403 6.750820\n9183 26.393442 0.624524 4.365783 3.397563 5.516881 6.325442 7.002654\n9184 26.399488 0.679772 4.057911 3.448431 5.748252 6.002542 7.256279\n9185 26.405457 0.712335 3.899972 3.461610 5.743822 5.899032 7.198548\n9186 26.411426 0.789720 3.585203 3.477962 5.503916 5.855267 6.895242\n9187 26.417588 0.838640 3.434605 3.485035 5.306021 5.870488 6.794261\n9188 26.423515 0.969152 3.159328 3.498653 4.871325 5.804193 6.928392\n9189 26.429636 1.050856 3.037718 3.502376 4.710702 5.603371 7.141698\n9190 26.435613 1.228298 2.831643 3.495413 4.672724 4.873036 7.563779\n9191 26.441672 1.312307 2.748307 3.486561 4.730988 4.503379 7.704526\n9192 26.447762 1.448657 2.622188 3.470137 4.833705 4.085026 7.841472\n9193 26.453844 1.503209 2.579959 3.464177 4.843437 3.997198 7.862798\n9194 26.460049 1.602586 2.533424 3.457343 4.826297 3.769371 7.874338\n9195 26.465957 1.654466 2.526165 3.453383 4.871456 3.659630 7.804667\n9196 26.471931 1.755240 2.536891 3.434412 5.016790 3.887029 7.363196\n9197 26.478183 1.795799 2.552544 3.419651 5.104097 4.252418 7.027988\n9198 26.483897 1.859509 2.605398 3.386487 5.367926 5.098161 6.434114\n9199 26.490020 1.882956 2.645536 3.370662 5.527146 5.418406 6.249784\n9200 26.496091 1.917246 2.755355 3.345677 5.790617 5.608559 5.999676\n9201 26.502091 1.930395 2.823764 3.336568 5.915321 5.460336 5.856454\n9202 26.508092 1.947618 2.986014 3.327939 6.121101 4.949583 5.583686\n9203 26.514229 1.948107 3.080507 3.330003 6.138789 4.707202 5.506042\n9204 26.520347 1.917019 3.297892 3.342619 5.904331 4.471297 5.493546\n9205 26.526270 1.881404 3.419300 3.348696 5.678408 4.430505 5.486013\n9206 26.532278 1.776844 3.676776 3.355489 5.191395 4.369015 5.465892\n9207 26.538526 1.711867 3.805609 3.355643 4.956057 4.337329 5.538362\n9208 26.544520 1.568998 4.051873 3.348768 4.491192 4.208929 5.876583\n9209 26.550528 1.497126 4.164704 3.343224 4.289981 4.042477 6.126278\n9210 26.556402 1.358497 4.359668 3.338500 4.042497 3.558219 6.768800\n9211 26.562351 1.295389 4.441482 3.342430 3.986690 3.376591 7.197259\n9212 26.568546 1.178909 4.572986 3.360446 3.858216 3.222815 8.065530\n9213 26.574464 1.128602 4.620897 3.371027 3.775535 3.269741 8.391086\n9214 26.581257 1.052875 4.675987 3.389750 3.699370 3.556681 8.743990\n9215 26.587353 1.025128 4.668880 3.403369 3.781301 3.734095 8.665723\n9216 26.592893 1.029666 4.638662 3.407441 3.852451 3.744671 8.619490\n9217 26.598795 1.044543 4.591057 3.410656 3.917962 3.773334 8.566407\n9218 26.604892 1.104095 4.457881 3.419157 4.106178 4.032502 8.454273\n9219 26.611401 1.174479 4.285832 3.435611 4.222988 4.666482 8.465649\n9220 26.617041 1.207744 4.191158 3.446214 4.191537 4.980034 8.455361\n9221 26.623429 1.277496 3.994345 3.458265 3.906872 5.159519 8.424325\n9222 26.628996 1.315218 3.892098 3.460268 3.520681 5.181255 8.434106\n9223 26.635471 1.416447 3.693741 3.483943 2.040030 5.283719 8.548538\n9224 26.641091 1.475315 3.607276 3.512620 1.398562 5.194157 8.664359\n9225 26.647588 1.632446 3.470855 3.609633 0.532840 4.993504 9.313999\n9226 26.653205 1.709314 3.429229 3.676853 0.470821 4.760163 9.544098\n9227 26.659507 1.831681 3.387894 3.812872 1.189382 3.745050 9.952303\n9228 26.665206 1.866180 3.378405 3.874622 1.581355 3.272223 10.070532\n9229 26.671676 1.889327 3.378918 4.006211 2.106185 2.965609 10.279421\n9230 26.677215 1.877335 3.382227 4.060955 2.092702 3.031094 10.322474\n9231 26.683840 1.808399 3.384687 4.173619 1.425618 3.202260 10.123609\n9232 26.689353 1.744026 3.381911 4.231161 0.853474 3.270633 9.921576\n9233 26.695678 1.540104 3.360214 4.333237 -0.351172 3.534051 9.354789\n9234 26.701338 1.399382 3.339074 4.378008 -0.734095 3.692413 9.007421\n9235 26.707836 1.052080 3.266977 4.464923 -0.590507 4.088394 8.540096\n9236 26.713485 0.864735 3.213007 4.509196 -0.182973 4.508424 8.565171\n9237 26.719994 0.528114 3.084291 4.602903 0.577211 5.209029 8.842552\n9238 26.725622 0.384825 3.017092 4.646725 0.810490 5.150532 8.915632\n9239 26.731983 0.141045 2.883011 4.704228 0.938041 4.521825 8.715943\n9240 26.737638 0.040944 2.824347 4.714764 0.967360 4.266291 8.595762\n9241 26.743885 -0.106163 2.738560 4.699327 1.224032 3.891954 8.676769\n9242 26.749741 -0.151605 2.712374 4.677097 1.409547 3.667181 8.774278\n9243 26.755935 -0.175807 2.692548 4.619201 1.588412 3.290478 8.912387\n9244 26.761781 -0.155484 2.697079 4.586640 1.462666 3.172065 8.903543\n9245 26.767974 -0.071082 2.730082 4.514063 0.827096 2.960044 8.756623\n9246 26.773743 -0.017846 2.758140 4.475482 0.429636 2.867476 8.700241\n9247 26.780005 0.100788 2.819131 4.393869 -0.365897 2.720545 9.187066\n9248 26.786399 0.155937 2.841653 4.351374 -0.731848 2.699847 9.549239\n9249 26.791967 0.257343 2.838700 4.266469 -1.065407 2.899112 10.270521\n9250 26.798019 0.304919 2.800247 4.228889 -0.973750 3.054154 10.502921\n9251 26.804049 0.399677 2.654070 4.166703 -0.672395 3.315665 10.777015\n9252 26.810003 0.446830 2.551383 4.138074 -0.600291 3.342253 10.910393\n9253 26.816222 0.525717 2.306611 4.071778 -0.500364 3.089226 10.903921\n9254 26.822207 0.553828 2.175942 4.029184 -0.316257 2.874819 10.837926\n9255 26.828284 0.587608 1.912879 3.929355 0.234747 2.612509 10.760406\n9256 26.834266 0.590463 1.787076 3.873417 0.526899 2.609041 10.704904\n9257 26.840271 0.573931 1.550576 3.747653 0.948927 2.600694 10.570122\n9258 26.846427 0.554962 1.443007 3.677654 1.035627 2.479012 10.438315\n9259 26.852479 0.507113 1.263724 3.514709 1.088581 2.037774 10.216822\n9260 26.858443 0.490134 1.197333 3.419843 1.126030 1.828375 10.118247\n9261 26.864410 0.474650 1.131082 3.195225 0.853310 1.484014 9.795015\n9262 26.870535 0.461731 1.137226 3.069647 0.488230 1.461307 9.643342\n9263 26.876413 0.437877 1.223800 2.806376 -0.078260 1.723863 9.289264\n9264 26.882676 0.429126 1.293588 2.680468 -0.185599 1.862956 9.207279\n9265 26.888896 0.421884 1.437325 2.449247 -0.248773 1.875735 9.291751\n9266 26.894665 0.416154 1.494714 2.343349 -0.240885 1.940175 9.547797\n9267 26.900660 0.398647 1.566899 2.144006 -0.143201 2.224167 10.004230\n9268 26.906692 0.388064 1.584655 2.046793 -0.092302 2.374617 10.074600\n9269 26.912793 0.336507 1.585890 1.856591 -0.019407 2.713881 9.793424\n9270 26.918739 0.292798 1.574874 1.765367 0.070058 2.794888 9.587302\n9271 26.924819 0.187846 1.557562 1.585341 0.407807 2.564833 9.535025\n9272 26.930850 0.138666 1.561791 1.490229 0.496437 2.383732 9.611091\n9273 26.936750 0.042278 1.609386 1.269721 0.426621 2.051232 9.335814\n9274 26.942976 -0.010108 1.647494 1.140246 0.278848 1.886994 9.008467\n9275 26.948938 -0.135683 1.743204 0.856863 -0.072930 1.682149 8.351929\n9276 26.954917 -0.205074 1.796039 0.709841 -0.185613 1.679824 8.214089\n9277 26.960874 -0.340896 1.899087 0.415079 -0.255022 1.714647 8.389997\n9278 26.967138 -0.398526 1.945626 0.270560 -0.165296 1.645058 8.549665\n9279 26.973139 -0.481156 2.023582 -0.010458 0.267165 1.390307 8.827669\n9280 26.979219 -0.509309 2.049940 -0.144740 0.489110 1.253726 8.895797\n9281 26.985300 -0.533565 2.066456 -0.391500 0.646123 1.018334 9.134700\n9282 26.992022 -0.523979 2.054878 -0.502959 0.559153 0.980411 9.468396\n9283 26.998225 -0.454066 1.989877 -0.701201 0.152144 1.322472 10.420651\n9284 27.004396 -0.320097 1.866027 -0.867991 -0.362687 1.872872 11.062050\n9285 27.010370 -0.240367 1.777687 -0.946635 -0.617107 2.042835 11.192229\n9286 27.016437 -0.083803 1.537362 -1.106951 -1.091397 2.256275 11.092964\n9287 27.022419 -0.013693 1.387685 -1.188958 -1.236489 2.425510 10.974785\n9288 27.028552 0.105957 1.045275 -1.353116 -1.387206 2.867657 10.894939\n9289 27.034407 0.151944 0.861936 -1.434480 -1.466325 3.050072 10.912069\n9290 27.040752 0.202449 0.491171 -1.603293 -1.751167 3.135693 10.799853\n9291 27.046701 0.198476 0.309379 -1.697561 -1.942438 3.013570 10.571156\n9292 27.052687 0.128883 -0.027888 -1.914073 -2.523686 2.548954 9.873087\n9293 27.058489 0.061381 -0.177554 -2.038435 -2.684577 2.276272 9.536746\n9294 27.064656 -0.097558 -0.437281 -2.313234 -2.485036 1.742571 9.410807\n9295 27.070676 -0.187606 -0.569456 -2.497548 -1.912920 1.444636 9.702072\n9296 27.076836 -0.285153 -0.713378 -2.760084 -1.388875 1.095812 10.129304\n9297 27.082778 -0.335890 -0.774570 -2.905704 -1.568521 0.919536 10.075259\n9298 27.088902 -0.458050 -0.861370 -3.211829 -2.461977 0.715440 9.391119\n9299 27.094893 -0.513630 -0.883190 -3.334440 -2.821953 0.777479 9.213905\n9300 27.100978 -0.596701 -0.915118 -3.546155 -3.051970 1.041938 9.455906\n9301 27.107131 -0.612457 -0.933777 -3.638327 -2.986595 1.168373 9.737840\n9302 27.112938 -0.606289 -0.994629 -3.788403 -2.952620 1.384547 10.061357\n9303 27.119033 -0.601612 -1.039321 -3.840907 -2.986855 1.525241 10.109937\n9304 27.125143 -0.621448 -1.149088 -3.903003 -3.083485 1.908141 10.241844\n9305 27.131228 -0.648187 -1.209065 -3.915659 -3.150903 2.089034 10.400246\n9306 27.137178 -0.711334 -1.330355 -3.916447 -3.214049 2.155403 10.803016\n9307 27.143183 -0.733946 -1.390047 -3.911290 -3.203707 2.062506 10.937419\n9308 27.149323 -0.734263 -1.510074 -3.892979 -3.183240 1.830949 10.996756\n9309 27.155304 -0.712038 -1.571671 -3.876440 -3.130358 1.735832 10.964244\n9310 27.161386 -0.640016 -1.691221 -3.825672 -2.934583 1.655015 10.893716\n9311 27.167406 -0.598671 -1.747274 -3.792575 -2.841228 1.654530 10.864856\n9312 27.173676 -0.518350 -1.854901 -3.729411 -2.811519 1.638788 10.783220\n9313 27.179611 -0.477242 -1.907602 -3.707538 -2.933922 1.601945 10.806118\n9314 27.185563 -0.388712 -2.016141 -3.685332 -3.291121 1.471898 10.943583\n9315 27.191604 -0.340903 -2.072720 -3.681098 -3.463874 1.412601 10.965042\n9316 27.197583 -0.257244 -2.188178 -3.672786 -3.636130 1.383510 10.804390\n9317 27.203711 -0.233734 -2.247752 -3.665642 -3.590203 1.350647 10.647785\n9318 27.210065 -0.236992 -2.374336 -3.647859 -3.244529 1.001262 10.557027\n9319 27.215743 -0.260669 -2.440320 -3.641797 -3.029640 0.750389 10.694426\n9320 27.221710 -0.335210 -2.573361 -3.642602 -2.781367 0.498192 11.036354\n9321 27.227953 -0.383882 -2.639343 -3.646690 -2.760035 0.620966 11.040059\n9322 27.233804 -0.494778 -2.769035 -3.649605 -2.806487 1.039893 10.786505\n9323 27.240073 -0.556232 -2.832485 -3.647162 -2.809069 1.111633 10.701150\n9324 27.245915 -0.683497 -2.958667 -3.643675 -2.719565 0.962799 10.746552\n9325 27.251923 -0.742987 -3.023001 -3.646942 -2.621153 0.863477 10.843408\n9326 27.258012 -0.846141 -3.157620 -3.665207 -2.402704 0.714398 11.013449\n9327 27.264157 -0.891026 -3.228090 -3.677942 -2.326236 0.700281 11.065866\n9328 27.270114 -0.972737 -3.373925 -3.708957 -2.198826 0.769506 10.992983\n9329 27.276179 -1.011685 -3.448395 -3.728914 -2.076624 0.809650 10.928270\n9330 27.282431 -1.094939 -3.595986 -3.783545 -1.673472 0.958580 10.826096\n9331 27.288833 -1.142987 -3.665875 -3.820084 -1.452925 1.021738 10.736187\n9332 27.294449 -1.250419 -3.793146 -3.915567 -1.107358 0.907503 10.414554\n9333 27.300882 -1.375457 -3.894130 -4.033715 -0.830130 0.486940 10.125449\n9334 27.306439 -1.442470 -3.927996 -4.094854 -0.677764 0.290043 10.083702\n9335 27.313013 -1.573547 -3.947278 -4.205873 -0.407600 0.267806 9.973503\n9336 27.318438 -1.637757 -3.928424 -4.253429 -0.276878 0.447752 9.814265\n9337 27.324852 -1.760831 -3.831241 -4.340994 0.054640 0.856288 9.360652\n9338 27.330546 -1.817905 -3.753548 -4.385950 0.285661 0.942059 9.133657\n9339 27.336935 -1.912453 -3.550758 -4.485967 0.994898 0.916169 8.795763\n9340 27.342736 -1.946868 -3.432853 -4.538020 1.400801 0.949435 8.618956\n9341 27.348883 -2.000649 -3.181390 -4.629913 2.091533 1.108817 8.197131\n9342 27.354668 -2.025587 -3.057074 -4.667379 2.338153 1.069368 8.042820\n9343 27.361053 -2.075080 -2.836379 -4.734538 2.649956 0.612743 8.064389\n9344 27.366890 -2.094792 -2.748211 -4.769951 2.737416 0.310339 8.280152\n9345 27.373231 -2.118852 -2.624602 -4.847230 2.703079 -0.053014 8.814321\n9346 27.378850 -2.120725 -2.586918 -4.884789 2.616136 -0.015086 9.045139\n9347 27.385106 -2.099199 -2.545670 -4.941213 2.455633 0.262383 9.265328\n9348 27.390975 -2.075944 -2.535301 -4.954889 2.437714 0.378578 9.259509\n9349 27.397193 -2.006007 -2.524406 -4.956307 2.439954 0.563323 9.322426\n9350 27.403104 -1.964125 -2.517890 -4.947892 2.381849 0.771131 9.432400\n9351 27.409027 -1.879905 -2.483395 -4.921890 2.103722 1.372871 9.554874\n9352 27.415072 -1.845140 -2.452519 -4.906477 2.007381 1.510356 9.449011\n9353 27.421111 -1.809094 -2.371167 -4.869221 2.211182 1.303638 8.997500\n9354 27.427088 -1.808347 -2.325135 -4.843979 2.525055 1.143281 8.800858\n9355 27.433312 -1.829545 -2.226790 -4.771356 3.239538 1.039956 8.564520\n9356 27.439409 -1.841216 -2.174051 -4.723879 3.479007 1.154812 8.496273\n9357 27.445442 -1.849061 -2.062304 -4.622591 3.511148 1.704469 8.416418\n9358 27.451230 -1.846299 -2.003841 -4.579026 3.386956 2.117464 8.460631\n9359 27.457391 -1.818991 -1.886131 -4.521891 3.337137 2.714757 8.698380\n9360 27.463260 -1.791427 -1.829365 -4.507991 3.511025 2.677633 8.806099\n9361 27.469518 -1.705573 -1.734782 -4.495741 4.126653 2.321937 8.868456\n9362 27.475463 -1.647333 -1.701395 -4.489452 4.358201 2.269250 8.867146\n9363 27.481578 -1.507776 -1.661942 -4.468418 4.287278 2.177656 9.100739\n9364 27.487567 -1.431583 -1.656728 -4.459197 3.982697 1.939511 9.345485\n9365 27.493566 -1.266552 -1.693617 -4.463951 2.989939 1.288832 9.920936\n9366 27.499689 -1.211987 -1.735111 -4.479481 2.590446 1.140329 10.130002\n9367 27.505827 -1.154227 -1.864811 -4.523048 2.141957 1.137968 10.634590\n9368 27.511810 -1.141056 -1.950089 -4.540823 2.007573 1.248781 10.807094\n9369 27.517895 -1.120400 -2.151869 -4.558027 1.811764 1.509498 10.870629\n9370 27.523982 -1.113091 -2.267400 -4.562757 1.763413 1.697877 10.739395\n9371 27.529885 -1.093748 -2.512189 -4.578722 1.690389 2.176620 10.196096\n9372 27.535987 -1.082845 -2.634096 -4.594491 1.698778 2.324787 9.955416\n9373 27.541985 -1.066621 -2.865214 -4.645744 2.072932 2.689540 9.347230\n9374 27.547848 -1.058541 -2.973203 -4.671490 2.457683 2.929810 9.060155\n9375 27.553961 -1.055167 -3.175194 -4.688540 3.390083 3.474102 8.288052\n9376 27.560038 -1.055559 -3.266227 -4.674208 3.826077 3.748709 7.908804\n9377 27.565997 -1.051500 -3.421577 -4.598198 4.417962 4.232444 7.101657\n9378 27.572185 -1.049260 -3.478446 -4.540909 4.700780 4.481591 6.670250\n9379 27.578150 -1.041525 -3.542511 -4.406166 5.402742 5.115466 5.950244\n9380 27.584274 -1.036275 -3.543874 -4.325991 5.698204 5.465711 5.679315\n9381 27.590277 -0.998678 -3.482532 -4.132909 5.881761 5.991686 5.287178\n9382 27.596319 -0.970805 -3.423487 -4.024714 5.729047 6.102957 5.181910\n9383 27.602489 -0.894573 -3.283113 -3.806423 5.272212 5.936934 5.415874\n9384 27.608389 -0.856198 -3.205237 -3.706223 5.288159 5.593681 5.412506\n9385 27.614423 -0.769740 -3.055265 -3.546814 5.860867 4.785678 5.492534\n9386 27.620320 -0.727284 -2.991930 -3.487592 6.199743 4.520797 5.401313\n9387 27.626474 -0.650302 -2.880410 -3.404806 6.552932 4.490212 5.280861\n9388 27.632638 -0.608205 -2.834512 -3.373617 6.466800 4.646855 5.164624\n9389 27.638744 -0.524317 -2.757309 -3.313003 6.000046 4.963914 4.877135\n9390 27.644836 -0.480686 -2.722979 -3.284337 5.688935 5.096354 4.806508\n9391 27.650621 -0.406767 -2.666893 -3.233226 5.100388 5.158870 4.985397\n9392 27.656621 -0.378060 -2.648490 -3.211385 4.980201 5.099001 5.169792\n9393 27.662812 -0.324352 -2.636226 -3.174282 5.023648 5.067227 5.528935\n9394 27.668853 -0.290108 -2.645853 -3.156179 5.078641 5.169017 5.615189\n9395 27.674808 -0.203663 -2.700218 -3.126202 5.212646 5.398480 5.650320\n9396 27.680905 -0.150201 -2.742841 -3.117371 5.189187 5.494580 5.596682\n9397 27.686866 -0.035496 -2.847406 -3.115464 4.930331 5.634966 5.313667\n9398 27.692846 0.014644 -2.905906 -3.122594 4.856353 5.669978 5.103245\n9399 27.698901 0.077843 -3.025221 -3.141065 4.965809 5.718103 4.629110\n9400 27.705592 0.093331 -3.132607 -3.121045 5.241441 5.626138 4.302752\n9401 27.711763 0.080549 -3.174714 -3.083847 5.430828 5.502872 4.226164\n9402 27.717520 0.058246 -3.206567 -3.027498 5.591266 5.514032 4.067854\n9403 27.723152 0.013283 -3.228424 -2.850127 5.690907 6.000922 3.467087\n9404 27.729608 -0.067321 -3.186006 -2.620352 6.034965 6.781692 2.807585\n9405 27.735192 -0.112466 -3.146940 -2.501913 6.292664 7.291124 2.542944\n9406 27.741662 -0.159151 -3.036950 -2.275046 6.562019 8.237875 2.272784\n9407 27.747252 -0.152425 -2.965097 -2.174792 6.440859 8.442233 2.282852\n9408 27.753693 -0.100388 -2.788998 -2.009077 5.769876 8.406397 2.297867\n9409 27.759354 -0.060481 -2.684014 -1.939947 5.487423 8.320232 2.215050\n9410 27.765766 0.046993 -2.458377 -1.833317 5.513889 7.601474 2.295756\n9411 27.771656 0.099099 -2.351897 -1.800581 5.721967 6.979937 2.515823\n9412 27.777840 0.202771 -2.172883 -1.780132 6.073051 5.839258 3.086631\n9413 27.783533 0.261663 -2.103601 -1.793315 6.170925 5.561402 3.303272\n9414 27.789683 0.403544 -2.006583 -1.851940 6.076692 5.778138 3.503442\n9415 27.795617 0.483013 -1.969517 -1.888000 5.878391 6.367053 3.430369\n9416 27.801709 0.648285 -1.892027 -1.958588 5.292823 8.001712 3.025659\n9417 27.807872 0.721709 -1.845836 -1.988806 4.993246 8.663654 2.783036\n9418 27.813952 0.851427 -1.729035 -2.029228 4.629905 9.213455 2.334642\n9419 27.819809 0.909493 -1.656150 -2.037550 4.615455 9.294827 2.197030\n9420 27.825873 1.018159 -1.488220 -2.017185 4.841301 9.323566 2.033090\n9421 27.831850 1.068349 -1.393505 -1.981848 5.095704 9.228393 1.917008\n9422 27.838159 1.150215 -1.179843 -1.861348 5.593968 8.884658 1.544895\n9423 27.843943 1.180441 -1.061675 -1.783889 5.762632 8.734567 1.307490\n9424 27.850103 1.217411 -0.803182 -1.623474 6.075200 8.589177 0.956304\n9425 27.856114 1.225059 -0.666313 -1.552583 6.122475 8.572362 0.808505\n9426 27.862239 1.240558 -0.397489 -1.439992 5.965637 8.799513 0.317593\n9427 27.868073 1.253718 -0.275892 -1.398226 5.917143 9.013862 -0.025508\n9428 27.874076 1.291320 -0.076783 -1.330850 6.007576 9.463282 -0.565338\n9429 27.880174 1.310874 0.000179 -1.299647 6.073896 9.564537 -0.708361\n9430 27.886289 1.344979 0.118662 -1.244249 6.061118 9.370150 -0.756132\n9431 27.892270 1.355259 0.177942 -1.221471 5.982990 9.068548 -0.625420\n9432 27.898394 1.352124 0.255028 -1.209348 5.976558 8.757727 -0.441929\n9433 27.904512 1.343957 0.300286 -1.211297 6.028345 8.718782 -0.340749\n9434 27.910389 1.330375 0.408745 -1.228213 5.863522 9.080578 -0.287575\n9435 27.916328 1.332034 0.448149 -1.236760 5.700212 9.283928 -0.347161\n9436 27.922470 1.344000 0.578298 -1.269442 5.266049 9.707125 -0.474080\n9437 27.928521 1.348788 0.624419 -1.283595 5.213963 9.816994 -0.514619\n9438 27.934647 1.348577 0.751599 -1.328582 5.256934 10.030974 -0.575335\n9439 27.940564 1.345107 0.816738 -1.353640 5.276233 10.172864 -0.596666\n9440 27.946546 1.316699 0.944519 -1.400123 5.133161 10.382928 -0.626884\n9441 27.952736 1.296470 1.007252 -1.421550 5.080743 10.497118 -0.965671\n9442 27.958662 1.248319 1.123953 -1.450714 5.173449 10.853769 -1.569719\n9443 27.964608 1.231103 1.179266 -1.450393 5.046625 11.122171 -1.740174\n9444 27.970946 1.195622 1.319202 -1.426183 5.079579 11.715136 -2.044251\n9445 27.976709 1.160421 1.382687 -1.406096 5.406302 11.799715 -2.260899\n9446 27.982763 1.064402 1.498637 -1.328360 5.900948 11.658175 -2.326895\n9447 27.988794 0.988768 1.559132 -1.274382 5.997861 11.465769 -2.015784\n9448 27.994877 0.819250 1.673196 -1.145534 5.410733 10.919516 -1.321088\n9449 28.000892 0.715768 1.724998 -1.058441 4.787996 10.545994 -1.190881\n9450 28.007063 0.472543 1.817302 -0.856413 3.599948 9.717577 -0.868580\n9451 28.013082 0.331821 1.856925 -0.752163 3.056856 9.426880 -0.596423\n9452 28.019208 0.035398 1.927089 -0.536714 2.568463 9.183836 0.154966\n9453 28.025060 -0.111766 1.951599 -0.434473 2.703468 9.142511 0.551805\n9454 28.031189 -0.385108 1.968460 -0.251945 3.039234 9.222249 0.809975\n9455 28.037340 -0.500118 1.961038 -0.166917 3.207652 9.345418 0.728439\n9456 28.043181 -0.675509 1.924456 -0.012003 3.605500 9.708631 0.377999\n9457 28.049309 -0.729244 1.906149 0.060590 3.732353 9.941826 0.180873\n9458 28.055449 -0.766993 1.894448 0.207917 4.000601 10.325672 -0.014279\n9459 28.061417 -0.762074 1.907105 0.278014 4.249954 10.405128 -0.012712\n9460 28.067531 -0.716064 1.968798 0.405802 4.641623 10.536703 0.285171\n9461 28.073503 -0.687078 2.017598 0.470528 4.580606 10.561591 0.393586\n9462 28.079453 -0.634918 2.147340 0.603692 4.058232 10.439409 0.380346\n9463 28.085453 -0.621552 2.224163 0.676934 3.654053 10.349955 0.323780\n9464 28.091455 -0.625661 2.389383 0.851933 3.050016 10.290702 0.220327\n9465 28.097615 -0.625702 2.473934 0.949157 2.891746 10.153304 0.548416\n9466 28.103925 -0.637714 2.653902 1.149716 2.439518 9.898224 1.197930\n9467 28.109696 -0.644009 2.746479 1.249154 2.186031 9.854777 1.344523\n9468 28.115744 -0.674841 2.931690 1.440452 2.006783 9.892877 1.329697\n9469 28.121851 -0.694730 3.024043 1.535769 2.082903 10.010792 1.391831\n9470 28.127875 -0.715229 3.204487 1.736037 2.463889 10.346380 1.960510\n9471 28.133896 -0.707424 3.290142 1.835266 2.716569 10.463984 2.143474\n9472 28.139899 -0.644982 3.436683 2.017828 3.017048 10.338417 2.305152\n9473 28.145945 -0.599042 3.491954 2.099172 3.152240 10.057066 2.345514\n9474 28.151973 -0.473791 3.568526 2.233279 3.446303 9.639605 2.638348\n9475 28.157929 -0.397792 3.591861 2.291903 3.522350 9.579282 2.807241\n9476 28.164050 -0.248391 3.615832 2.405767 3.650167 9.301929 3.061215\n9477 28.170627 -0.097340 3.612505 2.507248 3.623787 8.965611 3.272847\n9478 28.176176 -0.022174 3.608947 2.549626 3.590139 8.883092 3.372889\n9479 28.182570 0.113641 3.605361 2.609552 3.707568 8.734755 3.408513\n9480 28.188253 0.169082 3.610242 2.627123 3.749684 8.766855 3.293880\n9481 28.194570 0.247768 3.650707 2.650595 3.641633 9.152135 3.103383\n9482 28.200353 0.264675 3.690711 2.659374 3.527289 9.322931 3.055290\n9483 28.206762 0.245690 3.806976 2.677984 3.316629 9.334633 3.047393\n9484 28.212419 0.204920 3.875064 2.692391 3.280752 9.194326 3.011876\n9485 28.218618 0.060980 4.000065 2.735115 3.468245 8.823653 2.969906\n9486 28.224382 -0.036392 4.048995 2.764859 3.635387 8.722885 3.050038\n9487 28.230629 -0.268509 4.118849 2.846919 3.898381 8.683662 3.442465\n9488 28.236580 -0.402490 4.144067 2.896736 4.005324 8.631584 3.545185\n9489 28.242630 -0.702507 4.178396 3.003349 4.224486 8.304617 3.474018\n9490 28.248590 -0.860720 4.189948 3.059536 4.330383 8.150587 3.405525\n9491 28.254647 -1.177985 4.210526 3.170508 4.416728 8.193431 3.373015\n9492 28.260717 -1.341512 4.217143 3.220022 4.236207 8.549091 3.158185\n9493 28.266726 -1.606466 4.225996 3.332896 3.686731 8.133785 3.867996\n9494 28.272844 -1.710880 4.243197 3.387158 3.431412 7.592953 4.330630\n9495 28.278727 -1.856222 4.303611 3.477332 2.586327 7.248413 4.673716\n9496 28.284770 -1.908383 4.331071 3.519186 2.169686 7.192533 4.692307\n9497 28.290879 -1.973281 4.395913 3.596690 1.976744 6.847649 5.042495\n9498 28.296904 -1.978354 4.427557 3.624667 2.028370 6.676453 5.496186\n9499 28.303233 -1.929354 4.477358 3.658164 2.323522 6.195258 6.203793\n9500 28.308987 -1.864451 4.498610 3.657652 2.592668 5.886357 6.592727\n9501 28.315266 -1.683909 4.529154 3.625352 2.905626 5.414770 7.075654\n9502 28.321128 -1.574021 4.542247 3.604971 2.911042 5.306072 7.146932\n9503 28.327207 -1.339663 4.571447 3.551454 2.809941 5.176755 7.317907\n9504 28.333085 -1.215858 4.588500 3.519917 2.645798 5.118552 7.501536\n9505 28.339282 -0.966751 4.633452 3.463145 2.187255 5.004336 7.772711\n9506 28.345174 -0.835810 4.658490 3.438827 1.935167 4.846984 7.909651\n9507 28.351298 -0.591672 4.705601 3.397319 1.418091 4.520360 7.947314\n9508 28.357458 -0.480949 4.724972 3.384567 1.231731 4.386379 7.878958\n9509 28.363425 -0.307309 4.756096 3.383541 1.109506 4.268831 7.799607\n9510 28.369591 -0.244947 4.767408 3.396364 1.057647 4.370199 7.895960\n9511 28.375489 -0.170418 4.782200 3.439212 0.968657 4.544333 8.271453\n9512 28.381551 -0.159774 4.782613 3.459528 1.003253 4.439961 8.427107\n9513 28.387473 -0.197194 4.758057 3.492645 1.178223 3.950566 8.582489\n9514 28.393593 -0.240491 4.730821 3.510020 1.274516 3.725633 8.641436\n9515 28.399654 -0.362355 4.647535 3.550996 1.334789 3.560259 9.029048\n9516 28.405651 -0.436222 4.592894 3.575621 1.301035 3.504064 9.253935\n9517 28.411606 -0.611618 4.458070 3.628734 1.187388 3.270378 9.621490\n9518 28.417593 -0.708600 4.374225 3.651998 1.142554 3.163398 9.642369\n9519 28.423763 -0.920285 4.171790 3.681938 0.976975 3.109026 9.527746\n9520 28.429768 -1.027048 4.050436 3.686924 0.820019 3.072259 9.557763\n9521 28.435991 -1.242379 3.771972 3.677229 0.537168 2.933435 9.649134\n9522 28.441961 -1.337533 3.618992 3.666157 0.440661 2.829937 9.659479\n9523 28.448187 -1.519777 3.291004 3.642111 0.280072 2.543103 9.765152\n9524 28.453923 -1.606622 3.119038 3.626099 0.175612 2.342996 9.886204\n9525 28.459953 -1.775010 2.782842 3.575589 0.037789 2.030083 10.228486\n9526 28.465923 -1.856589 2.621503 3.540839 0.087555 1.988868 10.477472\n9527 28.472026 -1.997793 2.316676 3.458811 0.314524 2.056842 10.592979\n9528 28.478015 -2.054421 2.175555 3.413837 0.451069 2.057315 10.495820\n9529 28.484213 -2.142959 1.904016 3.320802 0.646783 1.812835 10.296689\n9530 28.490208 -2.175337 1.777760 3.275643 0.572552 1.633263 10.146337\n9531 28.496206 -2.201202 1.566049 3.190134 0.007149 1.330300 10.012534\n9532 28.502301 -2.202178 1.478565 3.148612 -0.342479 1.238620 9.956038\n9533 28.508320 -2.179882 1.345437 3.075312 -0.889519 1.140839 9.780218\n9534 28.514469 -2.158178 1.303111 3.046642 -1.035722 1.083315 9.731901\n9535 28.520420 -2.095935 1.261075 3.001873 -1.130949 0.867062 9.671663\n9536 28.526307 -2.055382 1.259389 2.984775 -1.107257 0.721366 9.616255\n9537 28.532419 -1.956725 1.285634 2.966970 -0.816218 0.389694 9.589740\n9538 28.538629 -1.905097 1.309858 2.968534 -0.646262 0.230505 9.623776\n9539 28.544687 -1.802826 1.379684 2.993785 -0.458771 0.005231 9.748710\n9540 28.550723 -1.753460 1.423917 3.015760 -0.458914 -0.118364 9.823639\n9541 28.556761 -1.671847 1.527034 3.070115 -0.507941 -0.396117 9.825153\n9542 28.562719 -1.643629 1.584054 3.099651 -0.528731 -0.460310 9.764023\n9543 28.568840 -1.609347 1.695589 3.158645 -0.514686 -0.502181 9.584528\n9544 28.575377 -1.601140 1.748993 3.186797 -0.403999 -0.543297 9.512779\n9545 28.580764 -1.590285 1.847202 3.242089 -0.027335 -0.593313 9.511048\n9546 28.587413 -1.589953 1.926106 3.294064 0.228602 -0.116920 9.456415\n9547 28.592993 -1.594485 1.954906 3.314669 0.198641 0.279043 9.370269\n9548 28.599465 -1.611088 1.984993 3.331228 0.003320 0.586884 9.123089\n9549 28.604962 -1.621202 1.985315 3.323446 -0.119386 0.444113 9.125549\n9550 28.611522 -1.644785 1.955921 3.269534 -0.325775 0.082916 9.383549\n9551 28.617092 -1.652488 1.929496 3.228165 -0.453800 -0.026878 9.560273\n9552 28.623577 -1.662923 1.864916 3.133352 -0.821274 -0.399868 9.798938\n9553 28.629081 -1.673904 1.829942 3.079854 -1.013479 -0.683198 9.791433\n9554 28.635681 -1.726979 1.749400 2.952975 -1.427145 -1.111782 9.686250\n9555 28.641379 -1.771540 1.693845 2.859903 -1.734631 -1.327055 9.792413\n9556 28.647616 -1.843280 1.605827 2.690289 -2.015884 -1.507729 10.031292\n9557 28.653505 -1.876006 1.556456 2.602990 -2.112519 -1.507872 9.983991\n9558 28.659721 -1.938978 1.442603 2.438101 -2.178303 -1.611063 9.642539\n9559 28.665490 -1.968587 1.379716 2.359425 -2.206805 -1.739705 9.576905\n9560 28.671875 -2.020039 1.253003 2.209575 -2.366923 -2.032254 9.669879\n9561 28.677593 -2.043838 1.194023 2.136096 -2.405604 -2.176545 9.727699\n9562 28.683844 -2.094616 1.082818 1.978818 -2.398104 -2.215241 9.757915\n9563 28.689750 -2.119519 1.030974 1.893974 -2.364538 -2.103427 9.750610\n9564 28.695857 -2.158870 0.941077 1.717893 -2.257870 -1.811268 9.775886\n9565 28.701879 -2.173281 0.902661 1.631289 -2.220368 -1.674936 9.755819\n9566 28.708216 -2.191197 0.833496 1.466858 -2.149640 -1.532165 9.536817\n9567 28.713628 -2.195697 0.798286 1.388237 -2.020846 -1.494493 9.360572\n9568 28.719692 -2.188439 0.718459 1.244598 -1.988108 -1.525299 9.352605\n9569 28.725761 -2.176648 0.675361 1.180165 -2.100417 -1.661235 9.471204\n9570 28.731956 -2.134726 0.588335 1.061113 -2.453949 -1.877120 9.722355\n9571 28.738094 -2.105619 0.543293 1.010159 -2.669708 -1.940570 9.758246\n9572 28.743958 -2.036745 0.456169 0.929448 -2.815593 -2.209033 9.737478\n9573 28.749986 -2.000399 0.413693 0.896887 -2.793887 -2.409468 9.761200\n9574 28.756065 -1.931764 0.328912 0.840810 -2.718523 -2.670338 9.752255\n9575 28.762056 -1.898490 0.286599 0.813418 -2.628761 -2.720007 9.708603\n9576 28.768416 -1.843686 0.204463 0.752605 -2.404249 -2.841897 9.614753\n9577 28.774156 -1.827282 0.166293 0.720422 -2.332533 -2.924262 9.567890\n9578 28.780175 -1.826314 0.097491 0.652528 -2.398971 -3.077633 9.464748\n9579 28.786299 -1.842059 0.067549 0.616764 -2.531937 -3.160901 9.406226\n9580 28.792396 -1.904415 0.017963 0.543056 -2.742419 -3.396490 9.173264\n9581 28.798220 -1.950810 -0.003137 0.505537 -2.794408 -3.537821 9.092670\n9582 28.804452 -2.062996 -0.042053 0.425199 -2.768920 -3.860553 9.054436\n9583 28.810527 -2.121615 -0.059401 0.380802 -2.662896 -4.043012 9.080380\n9584 28.816509 -2.234120 -0.095606 0.289161 -2.329402 -4.394513 9.137327\n9585 28.822581 -2.285452 -0.114655 0.247420 -2.129595 -4.495089 9.108924\n9586 28.828551 -2.366194 -0.146233 0.179295 -1.892526 -4.424929 8.999998\n9587 28.834829 -2.395170 -0.157414 0.153751 -1.929237 -4.313987 8.879566\n9588 28.840794 -2.426927 -0.168679 0.114038 -2.068264 -4.185457 8.639635\n9589 28.846686 -2.430072 -0.169190 0.096644 -2.068435 -4.146017 8.598517\n9590 28.852653 -2.400537 -0.161837 0.071438 -2.278894 -4.177325 8.690763\n9591 28.858674 -2.371513 -0.151630 0.065075 -2.370515 -4.127643 8.692677\n9592 28.864772 -2.299335 -0.120618 0.070960 -2.495754 -3.853665 8.594278\n9593 28.870796 -2.261529 -0.099600 0.086689 -2.498790 -3.742429 8.466735\n9594 28.876777 -2.182740 -0.049471 0.124577 -2.410979 -3.815885 8.351110\n9595 28.882791 -2.140384 -0.025312 0.137071 -2.360199 -3.974151 8.333704\n9596 28.888888 -2.053339 0.017187 0.142688 -2.133449 -4.254693 8.201171\n9597 28.894923 -2.012802 0.033176 0.138505 -2.063896 -4.374434 8.084311\n9598 28.901151 -1.956318 0.054064 0.123793 -2.115371 -4.674427 7.792641\n9599 28.907167 -1.943997 0.056899 0.112155 -2.158108 -4.880453 7.715362\n9600 28.913205 -1.954589 0.042580 0.074985 -2.128043 -5.311342 7.790140\n9601 28.919164 -1.974341 0.024606 0.048543 -2.059304 -5.436501 7.916820\n9602 28.925157 -2.029699 -0.030624 -0.018058 -1.938471 -5.392581 8.124224\n9603 28.931188 -2.059399 -0.065580 -0.055536 -1.921180 -5.261089 8.116362\n9604 28.937405 -2.117968 -0.143334 -0.134907 -1.970984 -4.899752 7.993769\n9605 28.943310 -2.144643 -0.184747 -0.176728 -2.001656 -4.768480 7.925922\n9606 28.949418 -2.180853 -0.267968 -0.265845 -2.049238 -4.711216 7.875215\n9607 28.955358 -2.188880 -0.307427 -0.312324 -2.106055 -4.810163 7.849811\n9608 28.961453 -2.193064 -0.374943 -0.403189 -2.305448 -5.271934 7.655365\n9609 28.968249 -2.196851 -0.422939 -0.481244 -2.467570 -5.719495 7.350407\n9610 28.974587 -2.201760 -0.437853 -0.511124 -2.518753 -5.867504 7.195048\n9611 28.980706 -2.219177 -0.447769 -0.551277 -2.547136 -6.258974 6.959486\n9612 28.986832 -2.228951 -0.443448 -0.562909 -2.515458 -6.527479 6.880498\n9613 28.992703 -2.247053 -0.414863 -0.566967 -2.434489 -6.971981 6.679697\n9614 28.998706 -2.252072 -0.392046 -0.557214 -2.408587 -7.094190 6.570719\n9615 29.004791 -2.246235 -0.333229 -0.511712 -2.390654 -7.205320 6.300846\n9616 29.010830 -2.232907 -0.298642 -0.477560 -2.417876 -7.217678 6.209487\n9617 29.017007 -2.182231 -0.226238 -0.398754 -2.364439 -7.153738 6.152402\n9618 29.023074 -2.142072 -0.190267 -0.359061 -2.215679 -7.099015 6.151852\n9619 29.028974 -2.032387 -0.124997 -0.283639 -1.726612 -7.070144 6.183519\n9620 29.035124 -1.967993 -0.098014 -0.248482 -1.476435 -7.058811 6.178308\n9621 29.041000 -1.838953 -0.052920 -0.180752 -1.245187 -7.134066 5.996122\n9622 29.047212 -1.784243 -0.036020 -0.147399 -1.313249 -7.400583 5.855019\n9623 29.053031 -1.713374 -0.026754 -0.084899 -1.605771 -8.245510 5.620901\n9624 29.059056 -1.698955 -0.036330 -0.058040 -1.792754 -8.614853 5.579543\n9625 29.065140 -1.716681 -0.091549 -0.009549 -2.148621 -8.960128 5.656206\n9626 29.071214 -1.741556 -0.131452 0.005504 -2.181771 -8.843266 5.680770\n9627 29.077359 -1.793097 -0.224583 0.019756 -2.089565 -8.399045 5.693249\n9628 29.083252 -1.812807 -0.274550 0.015506 -2.000849 -8.349675 5.883017\n9629 29.089343 -1.795745 -0.378954 -0.025063 -1.786516 -8.457619 6.445742\n9630 29.095187 -1.727219 -0.435127 -0.055136 -1.716154 -8.342428 6.810742\n9631 29.101343 -1.480745 -0.561127 -0.102894 -1.656187 -7.960923 6.761487\n9632 29.107478 -1.335901 -0.626822 -0.110708 -1.848596 -8.110560 6.217935\n9633 29.113474 -1.047156 -0.738652 -0.102374 -2.746991 -9.006600 5.045158\n9634 29.119365 -0.911992 -0.764244 -0.094806 -3.241537 -9.478269 4.798990\n9635 29.125447 -0.668764 -0.726507 -0.081092 -3.559158 -9.854006 4.880666\n9636 29.131588 -0.576211 -0.671594 -0.070745 -3.299981 -9.752677 4.769978\n9637 29.137681 -0.476271 -0.529764 -0.039042 -2.510063 -9.342950 4.156498\n9638 29.143668 -0.460697 -0.452733 -0.022249 -2.215940 -9.154306 3.958299\n9639 29.149669 -0.440843 -0.290279 0.001011 -1.950181 -8.998247 4.081078\n9640 29.155962 -0.417080 -0.206715 0.006827 -1.938050 -9.030230 4.274286\n9641 29.161821 -0.317355 -0.047174 0.015973 -2.062389 -9.260782 4.518769\n9642 29.168072 -0.240006 0.026269 0.025670 -2.166962 -9.436582 4.501956\n9643 29.173963 -0.048428 0.156011 0.068327 -2.357947 -9.814620 4.338319\n9644 29.179947 0.054131 0.209152 0.101262 -2.400766 -10.001759 4.274088\n9645 29.185943 0.251407 0.290732 0.175903 -2.467054 -10.210083 4.345054\n9646 29.191955 0.343603 0.317847 0.209363 -2.459648 -10.187092 4.462533\n9647 29.198078 0.502157 0.341172 0.255126 -2.320577 -9.923704 4.596052\n9648 29.204015 0.561752 0.335014 0.267220 -2.217604 -9.788861 4.576104\n9649 29.210160 0.640743 0.288525 0.272788 -2.132543 -9.826611 4.620261\n9650 29.216471 0.661142 0.253496 0.267260 -2.199902 -9.974994 4.723487\n9651 29.222226 0.656353 0.171579 0.244705 -2.433970 -10.265535 4.925472\n9652 29.229832 0.593802 0.079933 0.215174 -2.592739 -10.470320 4.994670\n9653 29.234386 0.552673 0.032634 0.198625 -2.645259 -10.523078 5.022922\n9654 29.240864 0.483514 -0.063883 0.159594 -2.676946 -10.487178 5.088079\n9655 29.246507 0.466492 -0.112082 0.137331 -2.671238 -10.435886 5.111409\n9656 29.252873 0.485100 -0.199161 0.095697 -2.664335 -10.248535 5.165214\n9657 29.258625 0.523550 -0.234894 0.081210 -2.643992 -10.116652 5.161813\n9658 29.264804 0.657212 -0.283064 0.075204 -2.535697 -10.004529 5.190657\n9659 29.270472 0.749504 -0.294668 0.086290 -2.429346 -10.094922 5.222404\n9660 29.276732 0.985181 -0.290749 0.144565 -2.054038 -10.382660 5.269970\n9661 29.282425 1.128043 -0.275124 0.194627 -1.812382 -10.447386 5.284492\n9662 29.289131 1.460824 -0.218831 0.340419 -1.387254 -10.311758 5.329906\n9663 29.294674 1.648397 -0.178508 0.433335 -1.225252 -10.143160 5.366239\n9664 29.300800 2.052296 -0.074247 0.642138 -1.058778 -9.738159 5.311894\n9665 29.306636 2.254403 -0.012400 0.750120 -1.125346 -9.550847 5.225208\n9666 29.312709 2.650643 0.121419 0.949047 -1.561029 -9.019752 5.174714\n9667 29.318745 2.843987 0.193103 1.030940 -1.874170 -8.744165 5.294642\n9668 29.324762 3.213294 0.340763 1.142501 -2.492345 -8.490915 5.677379\n9669 29.330891 3.381510 0.412314 1.168367 -2.805244 -8.406179 5.765423\n9670 29.336942 3.666533 0.541223 1.160995 -3.440288 -8.130773 5.774528\n9671 29.343085 3.774791 0.595736 1.131276 -3.673283 -8.043309 5.801210\n9672 29.349193 3.909046 0.678901 1.034400 -3.884562 -7.964694 6.109319\n9673 29.355208 3.936383 0.705630 0.972086 -3.867611 -7.809591 6.377459\n9674 29.361192 3.925466 0.727545 0.825162 -3.630207 -7.286575 6.874638\n9675 29.367145 3.890574 0.722014 0.743947 -3.430768 -7.015662 7.013669\n9676 29.373086 3.766372 0.675116 0.573392 -3.041456 -6.562874 7.129149\n9677 29.379300 3.688027 0.636580 0.485670 -2.895416 -6.340070 7.201446\n9678 29.385223 3.530408 0.537887 0.311935 -2.719216 -5.811135 7.504984\n9679 29.391332 3.458597 0.478819 0.231929 -2.639768 -5.500111 7.672860\n9680 29.397404 3.340073 0.339905 0.097398 -2.485973 -4.838785 8.010773\n9681 29.403376 3.303709 0.257177 0.045709 -2.368873 -4.494101 8.243701\n9682 29.409531 3.286789 0.061113 -0.020738 -1.995296 -3.980285 8.898260\n9683 29.415456 3.302013 -0.051092 -0.032317 -1.776505 -3.856822 9.215513\n9684 29.421692 3.355733 -0.293068 -0.002845 -1.496745 -3.840717 9.460806\n9685 29.427578 3.385456 -0.415640 0.041539 -1.498847 -3.868140 9.444384\n9686 29.433544 3.439533 -0.642649 0.186164 -1.808459 -3.987059 9.366302\n9687 29.439770 3.456178 -0.735637 0.278519 -2.173352 -4.207754 9.310605\n9688 29.445591 3.460364 -0.863751 0.477051 -3.227976 -4.576089 9.284970\n9689 29.451576 3.447310 -0.895183 0.574095 -3.709002 -4.569012 9.208993\n9690 29.457791 3.382555 -0.887736 0.748614 -4.348322 -4.437374 8.866487\n9691 29.463927 3.327911 -0.856668 0.824634 -4.469857 -4.392163 8.662859\n9692 29.469891 3.191309 -0.759471 0.945877 -4.255401 -4.102786 8.510218\n9693 29.475834 3.124261 -0.696782 0.989286 -4.007127 -3.828936 8.584864\n9694 29.481874 2.995584 -0.546418 1.051072 -3.204492 -3.190015 8.690250\n9695 29.487833 2.948014 -0.486756 1.064252 -2.768299 -2.982024 8.642583\n9696 29.493823 2.869922 -0.391757 1.067366 -1.993265 -2.529369 8.602021\n9697 29.500118 2.841200 -0.356477 1.060638 -1.730541 -2.250620 8.682065\n9698 29.505960 2.811715 -0.304146 1.036748 -1.318949 -1.961878 8.930309\n9699 29.511987 2.810637 -0.284921 1.021891 -1.181908 -1.963144 9.051104\n9700 29.518265 2.826323 -0.253344 0.991590 -1.134192 -1.929309 9.085602\n9701 29.524139 2.844339 -0.237382 0.974616 -1.218490 -1.852747 9.044607\n9702 29.530407 2.912804 -0.195545 0.938565 -1.562536 -1.682702 9.149635\n9703 29.536282 2.966568 -0.168045 0.921924 -1.744104 -1.549148 9.304167\n9704 29.542262 3.119005 -0.103637 0.894518 -2.168452 -1.127720 9.564926\n9705 29.548421 3.213204 -0.071019 0.884687 -2.400946 -0.949622 9.574560\n9706 29.554584 3.399091 -0.014371 0.868938 -2.883305 -1.052829 9.368161\n9707 29.560496 3.473049 0.010660 0.858538 -3.177461 -1.176600 9.197109\n9708 29.566389 3.584208 0.055908 0.823809 -3.654572 -0.841926 9.116497\n9709 29.572567 3.624950 0.076950 0.798704 -3.785711 -0.499798 9.230667\n9710 29.578489 3.670047 0.107547 0.731905 -3.730422 -0.135706 9.437809\n9711 29.584617 3.667003 0.109205 0.689294 -3.572302 -0.076877 9.384429\n9712 29.590619 3.609704 0.076289 0.585492 -3.110152 0.269424 9.153620\n9713 29.596757 3.560473 0.045584 0.525964 -2.863074 0.516124 9.137559\n9714 29.602615 3.430078 -0.032743 0.401744 -2.443092 0.899726 9.328082\n9715 29.608784 3.357116 -0.077086 0.340991 -2.273336 1.088612 9.386002\n9716 29.614797 3.222513 -0.168332 0.226782 -2.082959 1.603488 9.302382\n9717 29.621616 3.135282 -0.255868 0.126412 -2.070971 1.958324 9.134888\n9718 29.626854 3.116697 -0.296641 0.081911 -2.081948 1.963703 9.203774\n9719 29.632939 3.111890 -0.333702 0.042171 -2.117920 1.895120 9.308135\n9720 29.639052 3.137649 -0.393101 -0.016106 -2.255852 2.000554 9.411922\n9721 29.644990 3.165126 -0.415951 -0.029951 -2.330936 2.201370 9.362874\n9722 29.651217 3.243267 -0.443766 -0.020847 -2.554848 2.582201 9.187648\n9723 29.657674 3.295546 -0.448314 0.001022 -2.610971 2.570907 9.170020\n9724 29.662293 3.416899 -0.451346 0.063658 -2.424955 2.287843 9.304392\n9725 29.668265 3.479589 -0.453079 0.100253 -2.292966 2.305384 9.363061\n9726 29.674379 3.591664 -0.450070 0.185418 -2.179219 2.633282 9.263897\n9727 29.680198 3.629441 -0.443865 0.233204 -2.202981 2.871978 9.147046\n9728 29.686388 3.654816 -0.420299 0.327800 -2.438557 3.581782 8.827776\n9729 29.692393 3.649589 -0.401528 0.366812 -2.544868 3.908116 8.687690\n9730 29.698548 3.628131 -0.359406 0.414568 -2.618310 4.398995 8.468599\n9731 29.704428 3.617830 -0.339733 0.424895 -2.603128 4.657606 8.343740\n9732 29.710508 3.598751 -0.304599 0.423732 -2.536759 5.337848 8.103543\n9733 29.716519 3.584545 -0.292139 0.413811 -2.451269 5.586793 7.947822\n9734 29.722582 3.526340 -0.279909 0.380271 -2.102669 5.612143 7.619794\n9735 29.728676 3.478791 -0.279441 0.358343 -1.907588 5.502284 7.513483\n9736 29.734697 3.364102 -0.281434 0.302332 -1.627880 5.384914 7.426355\n9737 29.740629 3.306859 -0.282597 0.268729 -1.516172 5.425282 7.423460\n9738 29.746697 3.210734 -0.286652 0.198034 -1.244088 5.492360 7.475379\n9739 29.752792 3.177578 -0.289546 0.163420 -1.145453 5.625606 7.548483\n9740 29.758774 3.152179 -0.290436 0.098508 -1.248314 6.139946 7.555536\n9741 29.764801 3.157103 -0.289389 0.068698 -1.349340 6.371534 7.578732\n9742 29.770888 3.181068 -0.287863 0.017998 -1.590238 6.305313 7.703511\n9743 29.776951 3.194681 -0.283845 -0.000336 -1.756501 6.042724 7.728550\n9744 29.782993 3.218514 -0.268449 -0.018812 -1.962682 5.672973 7.676578\n9745 29.789016 3.223896 -0.258765 -0.015828 -2.149708 5.629061 7.521848\n9746 29.795182 3.202657 -0.231926 0.011951 -2.594714 5.621414 7.152487\n9747 29.801045 3.168737 -0.218850 0.030981 -2.912224 5.677987 6.917661\n9748 29.807071 3.055180 -0.201917 0.064784 -3.355037 6.195580 6.307583\n9749 29.813057 2.978709 -0.201035 0.077768 -3.423975 6.600496 6.035324\n9750 29.819261 2.798862 -0.218878 0.103448 -3.103867 7.352108 5.645751\n9751 29.825287 2.704438 -0.240030 0.120920 -2.622839 7.656438 5.578190\n9752 29.831473 2.512269 -0.309755 0.170714 -1.206662 8.022604 5.726851\n9753 29.838089 2.305840 -0.404539 0.240995 -0.389633 7.939567 6.040980\n9754 29.843475 2.199436 -0.449409 0.278263 -0.290400 7.891792 6.055855\n9755 29.849858 1.952155 -0.520214 0.362148 -0.654047 8.003482 5.735895\n9756 29.855503 1.834809 -0.536728 0.401948 -0.916007 8.045622 5.510406\n9757 29.862066 1.598839 -0.544054 0.474716 -1.430739 8.070008 5.099069\n9758 29.867694 1.489829 -0.536138 0.506190 -1.700515 8.117059 4.970005\n9759 29.874095 1.294004 -0.502407 0.565673 -2.028872 8.379716 4.728375\n9760 29.879746 1.199466 -0.477752 0.594672 -1.995908 8.506610 4.594032\n9761 29.886127 1.018881 -0.421529 0.653949 -1.760719 8.634915 4.317884\n9762 29.891841 0.937633 -0.391785 0.682372 -1.559972 8.668179 4.170794\n9763 29.898502 0.806569 -0.329364 0.730574 -1.336931 8.751431 3.975208\n9764 29.903874 0.758815 -0.298284 0.749633 -1.283747 8.776769 3.949577\n9765 29.910229 0.694600 -0.235996 0.771111 -1.138530 8.749280 4.084594\n9766 29.916002 0.673315 -0.203757 0.773795 -1.126249 8.714261 4.175385\n9767 29.922242 0.632199 -0.137878 0.767124 -1.038140 8.621389 4.282428\n9768 29.927980 0.606179 -0.106596 0.756438 -0.969488 8.597846 4.239055\n9769 29.934252 0.546164 -0.051367 0.721110 -0.943866 8.489526 4.190017\n9770 29.940118 0.513953 -0.029095 0.697477 -0.920713 8.381387 4.267240\n9771 29.946249 0.462823 0.007025 0.642880 -0.773132 8.220291 4.471968\n9772 29.952245 0.449277 0.022391 0.618486 -0.684804 8.310472 4.545465\n9773 29.958378 0.422347 0.051762 0.588495 -0.600014 8.485240 4.585681\n9774 29.964530 0.401275 0.066658 0.580284 -0.624147 8.526151 4.585295\n9775 29.970471 0.341688 0.095698 0.566167 -0.759816 8.664733 4.534214\n9776 29.976376 0.305730 0.106465 0.557086 -0.812328 8.774456 4.476857\n9777 29.982494 0.227555 0.113624 0.528675 -0.853317 9.005633 4.347757\n9778 29.988470 0.181320 0.108266 0.509377 -0.849611 9.062930 4.276330\n9779 29.994502 0.057620 0.077458 0.461276 -0.817637 8.958762 4.120034\n9780 30.000494 -0.025604 0.053234 0.432200 -0.747457 8.816378 4.092570\n9781 30.006507 -0.234777 -0.010545 0.366817 -0.465876 8.576554 4.278456\n9782 30.012579 -0.355610 -0.049187 0.332336 -0.286780 8.571238 4.435485\n9783 30.018741 -0.588090 -0.139105 0.264692 0.120741 8.967444 4.634293\n9784 30.024640 -0.687495 -0.190126 0.234358 0.290207 9.175380 4.639639\n9785 30.030770 -0.841230 -0.296896 0.184034 0.506901 9.152061 4.773098\n9786 30.036677 -0.890599 -0.347083 0.162573 0.612371 8.992079 4.928017\n9787 30.042580 -0.931019 -0.422935 0.127376 0.676406 8.710876 5.232614\n9788 30.048792 -0.932360 -0.445716 0.116133 0.574779 8.593472 5.319373\n9789 30.054758 -0.924070 -0.456397 0.103674 0.089764 8.355987 5.277950\n9790 30.060915 -0.918711 -0.443912 0.099199 -0.233696 8.237432 5.215405\n9791 30.066864 -0.915253 -0.392333 0.082713 -0.814639 8.013597 5.124813\n9792 30.073113 -0.921998 -0.358305 0.065992 -1.018469 7.936800 5.093051\n9793 30.079014 -0.963510 -0.282885 0.014266 -1.126772 8.011010 4.999324\n9794 30.085087 -1.002276 -0.246611 -0.016857 -0.999364 8.165040 4.916713\n9795 30.091135 -1.116603 -0.189689 -0.081902 -0.560798 8.688285 4.689341\n9796 30.097371 -1.184656 -0.172192 -0.116670 -0.324497 8.969218 4.575054\n9797 30.103107 -1.329651 -0.167499 -0.198156 0.001570 9.066982 4.554658\n9798 30.109147 -1.398605 -0.180114 -0.246544 0.099544 8.784954 4.695075\n9799 30.115242 -1.518937 -0.227979 -0.354380 0.280881 8.141202 5.209712\n9800 30.121238 -1.573998 -0.258796 -0.408555 0.411823 7.938789 5.435754\n9801 30.127367 -1.690234 -0.325606 -0.505060 0.718920 7.640145 5.768414\n9802 30.133388 -1.753637 -0.359125 -0.547064 0.856895 7.508814 5.862612\n9803 30.139366 -1.874320 -0.423942 -0.636633 0.990935 7.315403 6.040851\n9804 30.145360 -1.928375 -0.456158 -0.691454 0.938111 7.182069 6.125766\n9805 30.151419 -2.010602 -0.518816 -0.825333 0.667120 6.977283 6.259857\n9806 30.157543 -2.032455 -0.547752 -0.898832 0.463820 7.017643 6.298863\n9807 30.163791 -2.056198 -0.591555 -1.039008 0.078887 7.154032 6.143069\n9808 30.169666 -2.056725 -0.605522 -1.100969 -0.083460 7.192747 6.111928\n9809 30.175672 -2.032857 -0.610164 -1.206778 -0.358767 7.108253 6.155877\n9810 30.181593 -2.001569 -0.598579 -1.254324 -0.465001 7.059826 6.240252\n9811 30.187953 -1.906956 -0.552313 -1.342860 -0.712556 7.042804 6.339523\n9812 30.193795 -1.849923 -0.519459 -1.384370 -0.862011 7.039261 6.309386\n9813 30.199799 -1.737794 -0.439670 -1.459060 -1.083448 7.054574 6.204474\n9814 30.205828 -1.689241 -0.395644 -1.489555 -1.079024 7.102491 6.129996\n9815 30.211947 -1.616109 -0.306944 -1.535162 -0.860591 7.165274 6.126108\n9816 30.217925 -1.594047 -0.265850 -1.554131 -0.719959 7.090067 6.242505\n9817 30.223957 -1.577112 -0.200511 -1.595397 -0.552305 6.722407 6.541448\n9818 30.230586 -1.591844 -0.166215 -1.646021 -0.476123 6.399713 6.768755\n9819 30.236118 -1.610885 -0.162213 -1.672169 -0.432301 6.300877 6.880406\n9820 30.241983 -1.639116 -0.167034 -1.696440 -0.387970 6.143516 6.990698\n9821 30.248115 -1.729184 -0.197914 -1.736540 -0.473705 5.634832 7.291938\n9822 30.254725 -1.848453 -0.242970 -1.771976 -0.959851 5.214133 7.687531\n9823 30.260356 -1.924412 -0.271783 -1.795194 -1.370490 5.062683 7.893207\n9824 30.266779 -1.983120 -0.295076 -1.815089 -1.673410 4.993498 8.040417\n9825 30.272448 -2.084812 -0.345977 -1.858699 -2.095949 5.107143 8.287291\n9826 30.278757 -2.148971 -0.403691 -1.897273 -2.237940 5.312489 8.447706\n9827 30.284336 -2.165855 -0.438067 -1.912978 -2.222863 5.401654 8.443983\n9828 30.290833 -2.178231 -0.520512 -1.937547 -2.157669 5.505578 8.336470\n9829 30.296642 -2.172922 -0.568887 -1.948967 -2.159914 5.500942 8.344148\n9830 30.302853 -2.144306 -0.680562 -1.980206 -2.069570 5.336872 8.499590\n9831 30.308585 -2.122135 -0.743849 -2.000529 -1.998283 5.194149 8.644071\n9832 30.314937 -2.062616 -0.880050 -2.039565 -1.827553 4.914206 8.881671\n9833 30.320739 -2.027261 -0.948054 -2.054565 -1.793891 4.856311 8.985098\n9834 30.326960 -1.955945 -1.075559 -2.067819 -1.926720 4.713668 8.981939\n9835 30.332845 -1.924062 -1.132191 -2.065872 -2.008057 4.539133 8.928311\n9836 30.338966 -1.862330 -1.233109 -2.052319 -2.171266 4.175263 8.935050\n9837 30.344942 -1.827040 -1.276868 -2.042911 -2.300594 4.059176 8.970531\n9838 30.351070 -1.737644 -1.353976 -2.022790 -2.542970 3.931542 9.130244\n9839 30.356846 -1.688201 -1.390754 -2.011314 -2.590130 3.844948 9.196734\n9840 30.363230 -1.595233 -1.475510 -1.986075 -2.582353 3.634867 9.333899\n9841 30.368968 -1.558511 -1.531829 -1.979004 -2.500571 3.515948 9.469698\n9842 30.375073 -1.508250 -1.690957 -1.997335 -1.909644 2.928330 9.998074\n9843 30.381015 -1.492420 -1.795226 -2.025107 -1.350545 2.537237 10.348292\n9844 30.387163 -1.456421 -2.038327 -2.108532 -0.090677 2.229724 10.761606\n9845 30.393212 -1.426023 -2.165838 -2.157247 0.348817 2.333062 10.740798\n9846 30.399268 -1.362417 -2.406678 -2.255324 0.429927 2.258679 10.525652\n9847 30.405209 -1.323609 -2.510146 -2.308663 0.101987 2.024392 10.547801\n9848 30.411306 -1.230075 -2.656193 -2.439392 -0.520335 1.440552 10.637914\n9849 30.417389 -1.173002 -2.700438 -2.515753 -0.676458 1.200437 10.655718\n9850 30.423488 -1.040433 -2.742570 -2.667766 -0.751199 1.087092 10.566240\n9851 30.429616 -0.962115 -2.746262 -2.736444 -0.706395 1.205110 10.468029\n9852 30.435518 -0.767885 -2.748952 -2.845464 -0.709735 1.394185 10.412953\n9853 30.441470 -0.664674 -2.756058 -2.886939 -0.707424 1.431303 10.374056\n9854 30.447497 -0.472992 -2.798652 -2.963289 -0.772478 1.642423 10.280331\n9855 30.453646 -0.394872 -2.837871 -2.999092 -0.818372 1.774488 10.260665\n9856 30.459624 -0.273156 -2.951177 -3.057631 -0.571472 1.850584 10.554396\n9857 30.465614 -0.228037 -3.020159 -3.077016 -0.302566 1.706625 10.864585\n9858 30.471704 -0.155988 -3.163768 -3.087442 0.054772 1.315837 11.375240\n9859 30.477874 -0.122912 -3.229975 -3.080036 0.038169 1.289610 11.416334\n9860 30.483866 -0.046701 -3.339214 -3.056394 -0.284402 1.748862 11.243764\n9861 30.489829 -0.004000 -3.383808 -3.048072 -0.411245 1.916098 11.144907\n9862 30.495948 0.096812 -3.468202 -3.060901 -0.432775 1.770722 11.081084\n9863 30.501989 0.161445 -3.514916 -3.085442 -0.368177 1.636805 11.099153\n9864 30.507952 0.326828 -3.620691 -3.145413 0.109791 1.310032 11.316154\n9865 30.513987 0.420799 -3.677054 -3.166080 0.555199 1.081424 11.503531\n9866 30.519998 0.597118 -3.782570 -3.168013 1.339953 0.754926 11.668537\n9867 30.526078 0.668250 -3.825858 -3.152262 1.446423 0.743898 11.576076\n9868 30.532088 0.772822 -3.880379 -3.111576 1.228651 0.964010 11.268893\n9869 30.538096 0.817042 -3.888635 -3.094712 1.107664 1.135606 11.181706\n9870 30.544204 0.908415 -3.871613 -3.071063 1.218777 1.416897 11.033159\n9871 30.550267 0.957377 -3.852266 -3.061054 1.408948 1.554121 10.865106\n9872 30.556372 1.056547 -3.805379 -3.032126 1.788147 1.930534 10.266969\n9873 30.562392 1.103330 -3.779875 -3.011808 1.888455 2.112642 9.967844\n9874 30.568481 1.173979 -3.734083 -2.980628 1.781318 2.291507 9.566491\n9875 30.574453 1.192611 -3.719619 -2.983044 1.629213 2.306453 9.479275\n9876 30.580444 1.200455 -3.714064 -3.036004 1.420529 2.288747 9.305437\n9877 30.586416 1.191571 -3.721630 -3.078714 1.413269 2.320050 9.205223\n9878 30.592456 1.146221 -3.753742 -3.166182 1.522851 2.568773 9.001179\n9879 30.598509 1.109197 -3.776592 -3.205220 1.634877 2.679045 8.939144\n9880 30.604515 1.007443 -3.833637 -3.277793 1.983226 2.672626 9.063497\n9881 30.610686 0.946546 -3.866782 -3.315254 2.171977 2.621033 9.168256\n9882 30.616699 0.835915 -3.940070 -3.401529 2.556786 2.767546 9.240194\n9883 30.622655 0.794757 -3.982764 -3.449116 2.787514 2.947811 9.162800\n9884 30.628897 0.737724 -4.080484 -3.537820 3.323503 3.333042 8.713225\n9885 30.634826 0.721250 -4.133579 -3.572883 3.564565 3.537957 8.432690\n9886 30.640873 0.698063 -4.232884 -3.618825 3.741273 3.961399 7.777228\n9887 30.646732 0.682987 -4.272959 -3.632993 3.677655 4.063610 7.520051\n9888 30.652861 0.627449 -4.326092 -3.661885 3.495704 3.949786 7.336951\n9889 30.658817 0.586492 -4.334665 -3.680803 3.421582 3.865234 7.404050\n9890 30.665057 0.485816 -4.314800 -3.724491 3.338395 3.915453 7.515987\n9891 30.671049 0.424819 -4.286512 -3.744836 3.305030 4.026610 7.472066\n9892 30.677069 0.287472 -4.202535 -3.779762 3.132803 4.287314 7.089466\n9893 30.683177 0.213410 -4.147265 -3.796420 3.026990 4.457556 6.829697\n9894 30.689197 0.078057 -4.019343 -3.839139 2.872727 4.823282 6.435127\n9895 30.696013 -0.027238 -3.874945 -3.894315 2.785901 5.050755 6.198532\n9896 30.702421 -0.068680 -3.798475 -3.922302 2.750126 5.099775 6.148938\n9897 30.708431 -0.135762 -3.644299 -3.963166 2.733216 5.145483 6.127668\n9898 30.714401 -0.164664 -3.570144 -3.968589 2.805363 5.211092 6.138378\n9899 30.720332 -0.211498 -3.437204 -3.945957 3.145994 5.505163 6.229502\n9900 30.726449 -0.230358 -3.383339 -3.922713 3.362509 5.713495 6.299048\n9901 30.732361 -0.249454 -3.308128 -3.870651 3.775703 6.123341 6.361582\n9902 30.738550 -0.242935 -3.286178 -3.847295 3.970968 6.378578 6.290508\n9903 30.744557 -0.197540 -3.272085 -3.806640 4.201077 6.951257 5.964112\n9904 30.750670 -0.168776 -3.275206 -3.786012 4.200002 7.127087 5.717355\n9905 30.756642 -0.119059 -3.293488 -3.742678 4.010798 7.126736 5.502419\n9906 30.762588 -0.104138 -3.307490 -3.722430 3.870559 6.997240 5.535979\n9907 30.768807 -0.098775 -3.341783 -3.692970 3.615364 6.671918 5.840062\n9908 30.774706 -0.108263 -3.364098 -3.685600 3.509346 6.552845 6.015925\n9909 30.780737 -0.149733 -3.418403 -3.683985 3.263611 6.554473 6.164188\n9910 30.786801 -0.182240 -3.447869 -3.686130 3.125589 6.651443 6.060269\n9911 30.792704 -0.258436 -3.511514 -3.690318 2.874300 7.049230 5.721934\n9912 30.798981 -0.297197 -3.543582 -3.692590 2.784563 7.301815 5.522493\n9913 30.804901 -0.379751 -3.601404 -3.700387 2.665103 7.719650 5.085433\n9914 30.810940 -0.423390 -3.629762 -3.705881 2.610059 7.816349 4.926538\n9915 30.817076 -0.524218 -3.683577 -3.710806 2.485929 7.862639 4.737466\n9916 30.823188 -0.581073 -3.707482 -3.704845 2.405400 7.902627 4.762800\n9917 30.829047 -0.707629 -3.753842 -3.659750 2.254695 8.155456 4.968081\n9918 30.835191 -0.776757 -3.775967 -3.621231 2.220749 8.379016 5.008383\n9919 30.841109 -0.917720 -3.816499 -3.525795 2.202611 8.860911 5.172714\n9920 30.847172 -0.997687 -3.841931 -3.463712 2.189258 8.986521 5.319959\n9921 30.853189 -1.078586 -3.872901 -3.386207 2.054369 9.022748 5.364180\n9922 30.859437 -1.104361 -3.889326 -3.346040 1.909811 9.062812 5.365453\n9923 30.865417 -1.102503 -3.923795 -3.252109 1.608446 9.033809 5.390923\n9924 30.871353 -1.080356 -3.931530 -3.218380 1.524987 8.939100 5.445662\n9925 30.877336 -0.971027 -3.944114 -3.130690 1.301852 8.580903 5.690024\n9926 30.883566 -0.891103 -3.945914 -3.092706 1.209694 8.412482 5.735939\n9927 30.889636 -0.698469 -3.933208 -3.039254 1.069575 8.314867 5.582461\n9928 30.895503 -0.590217 -3.919181 -3.024142 0.980358 8.407452 5.450615\n9929 30.901606 -0.368020 -3.876019 -3.011684 0.709559 8.819436 4.957275\n9930 30.908222 -0.253346 -3.850080 -3.011469 0.615053 9.009276 4.688882\n9931 30.913711 -0.040409 -3.803093 -3.012989 0.746826 9.165451 4.289195\n9932 30.920346 0.131102 -3.767599 -3.006412 1.177267 9.144157 4.133093\n9933 30.925571 0.197381 -3.753429 -2.998104 1.363332 9.145326 4.062255\n9934 30.932214 0.279236 -3.726848 -2.967992 1.559497 9.239582 3.913911\n9935 30.937702 0.294229 -3.713155 -2.944036 1.599566 9.317409 3.833611\n9936 30.944222 0.281303 -3.680390 -2.873473 1.541191 9.441520 3.701466\n9937 30.949921 0.259323 -3.661355 -2.827415 1.403091 9.515287 3.677872\n9938 30.956275 0.208801 -3.614415 -2.716574 0.905250 9.575620 3.720178\n9939 30.961882 0.184532 -3.582047 -2.652565 0.609066 9.514194 3.819493\n9940 30.968369 0.145409 -3.475662 -2.494989 -0.014264 9.323948 3.971639\n9941 30.974029 0.141878 -3.428671 -2.440629 -0.192964 9.297068 3.962190\n9942 30.980344 0.166221 -3.275759 -2.298141 -0.320154 9.248548 3.875781\n9943 30.986167 0.201822 -3.185980 -2.229711 -0.155613 9.218021 3.818594\n9944 30.992415 0.360447 -2.956084 -2.077308 0.467077 9.107953 3.637668\n9945 30.998289 0.465418 -2.844001 -2.008340 0.756539 8.950193 3.595916\n9946 31.004410 0.721782 -2.610762 -1.863080 1.272412 8.501777 3.468657\n9947 31.010409 0.867144 -2.491455 -1.783524 1.506878 8.318597 3.313850\n9948 31.016787 1.173083 -2.247586 -1.606031 2.010004 8.131046 2.935112\n9949 31.022413 1.326413 -2.120806 -1.509936 2.289777 8.095453 2.710036\n9950 31.028536 1.630243 -1.844410 -1.314045 2.864446 8.126590 2.183579\n9951 31.034531 1.778809 -1.689039 -1.219155 3.104784 8.227817 1.902436\n9952 31.040705 2.063041 -1.333823 -1.045456 3.261634 8.824719 1.298252\n9953 31.046451 2.190305 -1.133661 -0.965988 3.027066 9.294363 0.939741\n9954 31.052650 2.387084 -0.707666 -0.810125 1.987829 10.162901 0.270413\n9955 31.058528 2.452756 -0.493218 -0.728337 1.419007 10.431003 0.038648\n9956 31.064600 2.523301 -0.075134 -0.543795 0.728001 10.718809 -0.041402\n9957 31.070608 2.531780 0.124450 -0.436398 0.744091 10.834415 0.008766\n9958 31.076650 2.494524 0.501789 -0.188477 1.313343 10.999802 0.010743\n9959 31.082676 2.451344 0.677435 -0.047636 1.687764 11.037866 -0.029955\n9960 31.088793 2.314779 1.000079 0.259383 2.296443 10.983979 -0.201152\n9961 31.094643 2.224788 1.145404 0.419618 2.531165 10.879957 -0.277654\n9962 31.100872 2.017361 1.397960 0.740824 3.008085 10.542376 -0.367527\n9963 31.106740 1.912514 1.503447 0.897311 3.275648 10.412445 -0.456661\n9964 31.112844 1.731650 1.678302 1.189705 3.779334 10.554863 -0.827757\n9965 31.118843 1.658430 1.753314 1.321475 4.028558 10.866528 -1.011793\n9966 31.124814 1.548150 1.901199 1.538293 4.414545 11.757004 -1.281602\n9967 31.130934 1.510774 1.985746 1.618605 4.371410 12.181025 -1.382064\n9968 31.137021 1.459361 2.188058 1.717253 3.772559 12.636287 -1.569009\n9969 31.143057 1.443576 2.303889 1.737482 3.375413 12.562789 -1.648252\n9970 31.149081 1.410385 2.554332 1.743566 2.629738 11.858839 -1.769985\n9971 31.155166 1.393610 2.680523 1.739055 2.402448 11.453938 -1.786781\n9972 31.161470 1.355043 2.922953 1.728338 2.238097 10.770224 -1.732390\n9973 31.167313 1.333319 3.037872 1.722970 2.256551 10.495653 -1.634223\n9974 31.173430 1.269613 3.249533 1.703231 2.474312 10.195813 -1.371011\n9975 31.179417 1.229106 3.347504 1.682456 2.595563 10.281575 -1.206173\n9976 31.185391 1.144529 3.531921 1.621987 2.737579 10.602056 -0.727607\n9977 31.191456 1.108163 3.618165 1.585351 2.809355 10.656404 -0.529455\n9978 31.197488 1.062867 3.779969 1.506494 2.869658 10.568750 -0.335290\n9979 31.203426 1.057238 3.857900 1.470209 2.867571 10.483082 -0.315418\n9980 31.209588 1.071876 4.016533 1.410601 2.923939 10.299816 -0.413014\n9981 31.215505 1.084520 4.100444 1.388710 2.867874 10.240364 -0.497687\n9982 31.221685 1.093081 4.279659 1.356413 2.898820 10.215920 -0.857585\n9983 31.227788 1.092094 4.375989 1.343583 3.139424 10.375893 -1.054458\n9984 31.233610 1.090214 4.585598 1.336169 3.376285 11.134878 -1.362316\n9985 31.239797 1.088524 4.698931 1.343099 3.514927 11.577272 -1.500605\n9986 31.245731 1.097969 4.932891 1.371156 3.975123 12.373713 -1.684316\n9987 31.251877 1.102527 5.049113 1.398948 4.030238 12.631519 -1.844431\n9988 31.257892 1.101179 5.267949 1.477777 3.789351 12.674717 -2.097172\n9989 31.264046 1.090630 5.368305 1.521936 3.443905 12.557091 -2.158733\n9990 31.269881 1.049309 5.557708 1.638584 2.564363 12.123604 -2.091982\n9991 31.275856 1.009147 5.644351 1.713302 2.307581 11.760065 -1.869695\n9992 31.282299 0.884796 5.791427 1.885199 2.056506 11.027987 -1.272497\n9993 31.288087 0.801645 5.849890 1.986382 2.026539 10.743551 -0.812538\n9994 31.294049 0.576294 5.923522 2.211628 2.296760 10.155140 0.301752\n9995 31.300189 0.434191 5.936316 2.331363 2.464107 9.795325 0.800349\n9996 31.305361 0.118613 5.912012 2.592341 2.680905 9.116473 1.552191\n9997 31.311312 -0.041794 5.873610 2.733278 2.745341 8.899177 1.837906\n9998 31.317438 -0.324704 5.758574 3.034364 2.669898 8.838521 2.427177\n9999 31.323310 -0.433865 5.688474 3.193841 2.573889 8.956113 2.730105\n10000 31.329368 -0.580838 5.531454 3.503660 2.410819 9.324210 3.097257\n10001 31.335427 -0.618505 5.449084 3.643296 2.286371 9.533457 3.170388\n10002 31.341420 -0.619763 5.288382 3.887079 2.028260 9.964938 3.524667\n10003 31.347355 -0.568384 5.209357 3.990595 1.967537 10.214561 3.863288\n10004 31.353474 -0.418360 5.061981 4.165416 2.069654 10.338068 3.919531\n10005 31.359585 -0.316704 4.981508 4.241825 2.171887 10.142160 3.966655\n10006 31.365786 -0.098503 4.807213 4.373378 2.437965 9.352458 4.161754\n10007 31.371752 0.014456 4.725446 4.424353 2.536685 8.932025 4.434133\n10008 31.377680 0.225621 4.566616 4.503027 2.580616 8.215077 4.876102\n10009 31.383786 0.315829 4.492124 4.532115 2.603448 7.937166 4.830866\n10010 31.389784 0.467540 4.363139 4.570982 2.595666 7.612812 4.700548\n10011 31.395747 0.530322 4.309019 4.586488 2.548679 7.513418 4.637086\n10012 31.401718 0.642102 4.232991 4.614167 2.622251 7.265458 4.502025\n10013 31.407866 0.696364 4.210836 4.623961 2.730608 7.101100 4.498317\n10014 31.413862 0.788212 4.186704 4.647439 2.930316 6.757397 4.411446\n10015 31.419899 0.822457 4.180672 4.662470 3.097379 6.690178 4.414132\n10016 31.425952 0.861551 4.172223 4.699589 3.450738 6.765943 4.680557\n10017 31.431961 0.862675 4.170831 4.723392 3.584984 6.801712 4.869967\n10018 31.438192 0.830773 4.181148 4.765606 3.775126 6.703657 5.116903\n10019 31.444156 0.799195 4.194367 4.777786 3.732200 6.622129 5.130444\n10020 31.450167 0.716050 4.239092 4.782894 3.573939 6.365225 4.841587\n10021 31.456152 0.673775 4.270142 4.774786 3.553092 6.158382 4.706401\n10022 31.462382 0.602713 4.343471 4.740271 3.711966 5.651638 4.689769\n10023 31.468255 0.576055 4.384940 4.718664 3.856324 5.428818 4.773811\n10024 31.474323 0.532893 4.474247 4.669345 4.251493 5.145485 5.074982\n10025 31.480384 0.511415 4.517551 4.642904 4.333042 5.026405 5.268996\n10026 31.486526 0.450280 4.588477 4.586907 4.312041 4.626193 5.623331\n10027 31.492444 0.409237 4.607513 4.554272 4.268333 4.466410 5.718478\n10028 31.498586 0.311166 4.596581 4.476423 4.087017 4.572718 5.949607\n10029 31.505202 0.221870 4.531693 4.419169 4.008718 4.625515 6.380011\n10030 31.510582 0.175755 4.482271 4.394123 4.015447 4.448237 6.551410\n10031 31.517196 0.069985 4.345510 4.351083 4.045374 4.022969 6.884363\n10032 31.522705 0.003779 4.259754 4.331411 4.085675 3.909250 7.077845\n10033 31.529096 -0.156618 4.072404 4.300128 3.991563 3.796566 7.739877\n10034 31.534793 -0.245689 3.976615 4.291383 3.822037 3.725669 8.073851\n10035 31.541139 -0.422992 3.791383 4.281296 3.406881 3.438354 8.386303\n10036 31.546840 -0.508500 3.704039 4.278000 3.205045 3.234868 8.405843\n10037 31.553428 -0.666482 3.541506 4.279398 2.963659 2.924297 8.394936\n10038 31.558931 -0.735391 3.469412 4.283214 2.919594 2.867627 8.417258\n10039 31.565183 -0.848431 3.343606 4.295693 2.863700 2.799331 8.443877\n10040 31.571081 -0.893204 3.287291 4.303707 2.878812 2.689720 8.433470\n10041 31.577311 -0.958052 3.179727 4.317723 3.108875 2.270835 8.562994\n10042 31.583145 -0.977177 3.126071 4.322573 3.291003 2.027129 8.672962\n10043 31.589182 -0.976284 3.015025 4.329559 3.615762 1.628915 8.963557\n10044 31.595131 -0.959780 2.958392 4.328563 3.730365 1.512482 9.051889\n10045 31.601551 -0.892686 2.846592 4.312339 3.738800 1.283252 9.230783\n10046 31.607213 -0.848880 2.792774 4.295820 3.667701 1.114976 9.288199\n10047 31.613513 -0.749815 2.688703 4.234736 3.397516 0.720064 9.355153\n10048 31.619149 -0.700344 2.636969 4.189783 3.179832 0.531630 9.338949\n10049 31.625490 -0.601893 2.539546 4.080104 2.624413 0.256953 9.252433\n10050 31.631309 -0.563607 2.497010 4.018670 2.331745 0.184537 9.299524\n10051 31.637575 -0.517470 2.425091 3.891662 1.814464 0.058210 9.455221\n10052 31.643453 -0.510876 2.396386 3.828041 1.612032 -0.036211 9.580986\n10053 31.649664 -0.527715 2.345763 3.695470 1.439376 -0.162587 9.943906\n10054 31.655442 -0.553949 2.322927 3.626947 1.520902 -0.212983 10.098348\n10055 31.661473 -0.623963 2.276915 3.491160 2.059179 -0.224654 10.231132\n10056 31.667567 -0.658659 2.249678 3.426394 2.377657 -0.173470 10.162725\n10057 31.673604 -0.706969 2.180184 3.305502 2.982460 -0.036451 9.767629\n10058 31.679554 -0.718795 2.139093 3.249999 3.241308 0.013259 9.559398\n10059 31.685564 -0.702209 2.053378 3.159217 3.326443 -0.000419 9.517956\n10060 31.691632 -0.680359 2.016009 3.117889 3.362008 -0.030400 9.525761\n10061 31.697935 -0.612474 1.960247 3.039775 3.057467 -0.248875 9.773762\n10062 31.703847 -0.576953 1.940569 3.006176 2.844372 -0.343475 9.841991\n10063 31.709909 -0.516403 1.920067 2.938754 2.569366 -0.431230 9.844205\n10064 31.715906 -0.484967 1.914082 2.907466 2.251546 -0.525272 9.839665\n10065 31.721873 -0.436200 1.906446 2.846899 1.752295 -0.908901 9.726963\n10066 31.727974 -0.415985 1.901637 2.808344 1.549223 -1.130061 9.769688\n10067 31.734085 -0.403631 1.892996 2.722163 1.052529 -1.761356 9.779593\n10068 31.740198 -0.417212 1.888175 2.673726 0.858305 -2.097618 9.832986\n10069 31.746160 -0.498236 1.874470 2.554606 0.552758 -2.427305 10.007045\n10070 31.752153 -0.557025 1.867685 2.489641 0.500218 -2.407211 10.111945\n10071 31.758267 -0.684979 1.850233 2.363076 0.454968 -2.337390 10.568883\n10072 31.764239 -0.748433 1.834484 2.297059 0.431249 -2.346795 10.661136\n10073 31.770362 -0.850932 1.783347 2.162360 0.603687 -2.379537 10.546575\n10074 31.776428 -0.885498 1.743676 2.100463 0.839729 -2.353132 10.453607\n10075 31.782322 -0.910792 1.652140 1.999425 1.146151 -2.201737 10.430958\n10076 31.788398 -0.897214 1.605110 1.961638 1.199224 -2.107204 10.435828\n10077 31.794324 -0.827169 1.512869 1.914879 1.311560 -2.020131 10.346697\n10078 31.800482 -0.772523 1.469211 1.904121 1.339177 -2.025003 10.303694\n10079 31.806437 -0.636164 1.394431 1.894467 1.382664 -1.951991 10.345597\n10080 31.812726 -0.560210 1.363724 1.892117 1.343307 -1.872020 10.393456\n10081 31.818611 -0.412047 1.316094 1.891220 1.140815 -1.700704 10.354780\n10082 31.824746 -0.341040 1.299307 1.890549 0.991385 -1.634675 10.289014\n10083 31.830686 -0.210781 1.277315 1.886756 0.570824 -1.496305 10.231501\n10084 31.836801 -0.149509 1.271094 1.884298 0.339815 -1.458190 10.202463\n10085 31.842777 -0.032694 1.266101 1.874895 -0.102744 -1.514739 10.121221\n10086 31.848821 0.020528 1.262958 1.867145 -0.293973 -1.615754 10.071178\n10087 31.854767 0.108204 1.252984 1.845608 -0.552160 -1.807076 9.990262\n10088 31.860833 0.140089 1.246582 1.832782 -0.603458 -1.843243 10.014730\n10089 31.867005 0.175709 1.230202 1.805548 -0.651463 -1.861882 10.048962\n10090 31.873057 0.173501 1.220954 1.794851 -0.685122 -1.863642 10.026312\n10091 31.879034 0.132135 1.196210 1.770748 -0.776925 -1.869351 9.978204\n10092 31.885027 0.094512 1.181277 1.755219 -0.772809 -1.914309 9.959282\n10093 31.891254 -0.007206 1.144759 1.710121 -0.561449 -2.086780 10.048394\n10094 31.897136 -0.068307 1.123789 1.676532 -0.404375 -2.156366 10.071127\n10095 31.903362 -0.196091 1.080475 1.584476 -0.216396 -2.347750 10.075981\n10096 31.909310 -0.259079 1.056647 1.528092 -0.163460 -2.420457 10.094416\n10097 31.915276 -0.339772 1.009743 1.378882 -0.339054 -2.749245 9.937303\n10098 31.921333 -0.372861 0.991284 1.276252 -0.737674 -2.913962 9.981863\n10099 31.927413 -0.411271 0.953888 1.003806 -1.689807 -3.287937 10.146411\n10100 31.933299 -0.418790 0.939595 0.840149 -2.011371 -3.428234 10.121539\n10101 31.939320 -0.420175 0.901769 0.488830 -2.347869 -3.528231 10.229079\n10102 31.945894 -0.419450 0.870575 0.313136 -2.437606 -3.569650 10.182590\n10103 31.951562 -0.415351 0.787300 -0.031181 -2.576263 -3.805163 10.322754\n10104 31.958161 -0.413494 0.733292 -0.205290 -2.645898 -3.923983 10.453048\n10105 31.963657 -0.409059 0.607643 -0.558147 -2.782528 -3.846592 10.515241\n10106 31.970084 -0.404337 0.465959 -0.904531 -2.838292 -3.488307 10.520121\n10107 31.975781 -0.403134 0.389661 -1.069342 -2.898894 -3.284466 10.486293\n10108 31.982298 -0.384551 0.232784 -1.374502 -3.021895 -3.005530 10.489126\n10109 31.987876 -0.361117 0.152967 -1.518654 -3.080918 -2.959139 10.554335\n10110 31.994206 -0.278110 -0.002888 -1.799232 -3.239009 -2.962008 10.654379\n10111 31.999809 -0.219878 -0.075690 -1.934838 -3.282035 -2.959100 10.629277\n10112 32.006078 -0.083779 -0.208244 -2.188146 -3.292097 -2.795421 10.370050\n10113 32.012022 -0.011393 -0.267258 -2.300359 -3.276484 -2.639057 10.241236\n10114 32.018446 0.142569 -0.371949 -2.493169 -3.148706 -2.385108 10.219276\n10115 32.024105 0.224288 -0.418975 -2.577553 -3.034154 -2.387818 10.258356\n10116 32.030312 0.388271 -0.506291 -2.731067 -2.749796 -2.638332 10.256250\n10117 32.036436 0.463762 -0.548251 -2.801999 -2.613158 -2.803173 10.184838\n10118 32.042353 0.586453 -0.625935 -2.934890 -2.473100 -3.059622 10.047042\n10119 32.048110 0.633469 -0.657624 -2.995448 -2.454992 -3.125301 10.057899\n10120 32.054252 0.697572 -0.699612 -3.106039 -2.453887 -3.207897 10.146722\n10121 32.060169 0.719071 -0.711292 -3.160856 -2.481063 -3.275980 10.171200\n10122 32.066432 0.752448 -0.727645 -3.283930 -2.548273 -3.492793 10.140385\n10123 32.072415 0.767892 -0.737592 -3.356628 -2.547563 -3.616233 10.129058\n10124 32.078473 0.801683 -0.766716 -3.523370 -2.460350 -3.797279 10.134527\n10125 32.084436 0.821978 -0.786268 -3.612571 -2.350841 -3.797360 10.118890\n10126 32.090458 0.872066 -0.834741 -3.790292 -1.970536 -3.572154 10.064268\n10127 32.096557 0.902311 -0.863197 -3.875339 -1.746708 -3.365031 10.049881\n10128 32.102741 0.968121 -0.923659 -4.033525 -1.382355 -2.931376 9.987517\n10129 32.108705 0.999920 -0.952865 -4.107887 -1.296506 -2.720831 9.937362\n10130 32.114725 1.053772 -1.003945 -4.249729 -1.269794 -2.154097 9.736580\n10131 32.120884 1.073694 -1.023313 -4.315937 -1.282282 -1.788861 9.653281\n10132 32.126833 1.092340 -1.048466 -4.434678 -1.303607 -1.219166 9.651958\n10133 32.132773 1.088681 -1.055067 -4.488346 -1.265443 -1.118776 9.695157\n10134 32.138772 1.054317 -1.062995 -4.591522 -1.079077 -1.145583 9.738619\n10135 32.144783 1.025204 -1.065456 -4.642515 -0.945382 -1.172347 9.726168\n10136 32.150882 0.948733 -1.066522 -4.746736 -0.639930 -1.205495 9.774249\n10137 32.156851 0.905031 -1.063673 -4.800346 -0.496251 -1.242899 9.826166\n10138 32.163127 0.823238 -1.048393 -4.906407 -0.214770 -1.347378 9.956326\n10139 32.169177 0.789961 -1.032458 -4.956534 -0.056158 -1.414493 10.016478\n10140 32.175180 0.737761 -0.984827 -5.044573 0.326174 -1.551021 10.055673\n10141 32.180948 0.719731 -0.954893 -5.079202 0.541552 -1.611674 10.037592\n10142 32.187142 0.705730 -0.886373 -5.123025 1.002847 -1.497861 10.035747\n10143 32.193065 0.711196 -0.848777 -5.131710 1.186045 -1.281922 10.066874\n10144 32.199186 0.743918 -0.768909 -5.121667 1.355249 -0.607489 10.158075\n10145 32.205389 0.768761 -0.726523 -5.105375 1.354227 -0.234213 10.163714\n10146 32.211213 0.827503 -0.639086 -5.060420 1.287033 0.350251 10.086741\n10147 32.217766 0.857423 -0.596739 -5.033781 1.262362 0.531753 10.058934\n10148 32.223433 0.914468 -0.517417 -4.972510 1.360224 0.670328 10.051896\n10149 32.229372 0.942961 -0.480930 -4.936668 1.457497 0.671543 10.072048\n10150 32.235389 1.001419 -0.418994 -4.852926 1.704690 0.535889 10.166813\n10151 32.241493 1.040773 -0.388482 -4.796159 1.813267 0.554982 10.305539\n10152 32.247462 1.104297 -0.351285 -4.703639 1.765288 1.141892 10.541064\n10153 32.253471 1.130969 -0.336653 -4.658121 1.646793 1.648246 10.604767\n10154 32.259531 1.161245 -0.315130 -4.574936 1.259386 2.691975 10.543467\n10155 32.265577 1.163015 -0.309556 -4.540888 1.045397 3.012746 10.377038\n10156 32.271825 1.136383 -0.314093 -4.491748 0.718347 3.054460 9.973897\n10157 32.277790 1.108652 -0.324969 -4.473781 0.644545 2.861581 9.776157\n10158 32.283825 1.028693 -0.359391 -4.436046 0.547249 2.364599 9.536484\n10159 32.289792 0.977439 -0.380393 -4.411467 0.479737 2.088077 9.514549\n10160 32.295792 0.855819 -0.422426 -4.352942 0.273912 1.644224 9.470247\n10161 32.301954 0.790381 -0.442161 -4.321063 0.139673 1.564230 9.399497\n10162 32.308027 0.661069 -0.479832 -4.252137 -0.218787 1.743837 9.237660\n10163 32.314100 0.604138 -0.498013 -4.214279 -0.416462 1.941682 9.190335\n10164 32.320090 0.530584 -0.532917 -4.125965 -0.696608 2.367567 9.173216\n10165 32.326229 0.516737 -0.549335 -4.072730 -0.745791 2.548405 9.202468\n10166 32.332193 0.521798 -0.574250 -3.947445 -0.739588 2.766543 9.326543\n10167 32.338357 0.532412 -0.578988 -3.878710 -0.733286 2.756322 9.427253\n10168 32.344228 0.556419 -0.566715 -3.741524 -0.653388 2.483002 9.636843\n10169 32.350319 0.568812 -0.551069 -3.677755 -0.538311 2.268034 9.733944\n10170 32.356360 0.604356 -0.507292 -3.562395 -0.171928 1.929434 9.905439\n10171 32.363100 0.670583 -0.453164 -3.456095 0.329321 1.778635 9.903505\n10172 32.368445 0.714796 -0.425567 -3.403674 0.568881 1.759425 9.793095\n10173 32.375000 0.812425 -0.377574 -3.304549 0.958646 1.806720 9.460141\n10174 32.380445 0.860093 -0.359192 -3.260300 1.135076 1.886243 9.294116\n10175 32.387003 0.944236 -0.331391 -3.184020 1.478265 2.246392 8.962415\n10176 32.392658 0.976678 -0.320661 -3.150675 1.600423 2.586763 8.799006\n10177 32.399181 1.011418 -0.302644 -3.087537 1.553911 3.439148 8.429541\n10178 32.404691 1.010119 -0.293844 -3.056278 1.374636 3.784820 8.306144\n10179 32.411118 0.960468 -0.274038 -2.997255 0.796505 4.092369 8.345479\n10180 32.416789 0.910039 -0.262899 -2.971025 0.469262 4.080210 8.486115\n10181 32.423197 0.761066 -0.243454 -2.925450 -0.032372 3.798634 8.917621\n10182 32.428794 0.669089 -0.239537 -2.904471 -0.210693 3.568806 9.180847\n10183 32.435374 0.476268 -0.252438 -2.863438 -0.403212 2.975096 9.827007\n10184 32.440860 0.388399 -0.271968 -2.844821 -0.423485 2.685039 10.160008\n10185 32.447210 0.260898 -0.341070 -2.814473 -0.342453 2.230648 10.768127\n10186 32.452884 0.229522 -0.389248 -2.802794 -0.228122 2.100313 10.995064\n10187 32.459174 0.244716 -0.498298 -2.783736 0.170800 2.191406 11.123995\n10188 32.464992 0.290591 -0.552134 -2.773611 0.457083 2.420501 10.985899\n10189 32.471124 0.450506 -0.642326 -2.748486 1.120042 3.154944 10.235137\n10190 32.476966 0.556177 -0.674555 -2.734041 1.385472 3.581732 9.759687\n10191 32.483259 0.794448 -0.710999 -2.705597 1.597011 4.303370 8.785363\n10192 32.489196 0.912357 -0.716181 -2.694049 1.515422 4.538739 8.329014\n10193 32.495318 1.102424 -0.710962 -2.681257 1.121643 4.639305 7.746185\n10194 32.501478 1.156280 -0.704346 -2.680097 0.922800 4.518170 7.702826\n10195 32.507391 1.171605 -0.686768 -2.685074 0.595722 4.042341 8.088121\n10196 32.513473 1.134378 -0.676426 -2.691498 0.457131 3.701224 8.335473\n10197 32.519483 0.981424 -0.656712 -2.712098 0.114896 2.816405 8.857346\n10198 32.525435 0.877333 -0.646395 -2.726112 -0.076545 2.350147 9.053843\n10199 32.531562 0.661450 -0.625009 -2.758950 -0.371397 1.677154 9.381050\n10200 32.537587 0.563314 -0.616903 -2.774845 -0.503707 1.497255 9.548715\n10201 32.543684 0.406574 -0.615441 -2.797419 -0.739748 1.330199 9.871017\n10202 32.549561 0.355486 -0.627871 -2.803534 -0.830456 1.302892 10.047078\n10203 32.555695 0.311716 -0.692481 -2.806126 -0.842452 1.313038 10.503062\n10204 32.561662 0.319026 -0.745944 -2.804495 -0.749322 1.401043 10.725913\n10205 32.567983 0.391708 -0.891649 -2.799459 -0.588282 1.933731 11.010138\n10206 32.573814 0.451773 -0.980387 -2.797143 -0.590386 2.350825 11.021987\n10207 32.579834 0.602784 -1.178651 -2.797163 -0.756196 3.292680 10.795384\n10208 32.585809 0.688160 -1.285676 -2.799948 -0.876248 3.774301 10.608145\n10209 32.591962 0.869110 -1.512635 -2.814424 -0.981803 4.657099 10.140472\n10210 32.597939 0.957930 -1.630526 -2.825948 -0.907997 5.020470 9.921275\n10211 32.603932 1.121042 -1.870114 -2.850928 -0.510386 5.538068 9.522323\n10212 32.609969 1.188305 -1.986959 -2.862870 -0.261764 5.701605 9.285337\n10213 32.616066 1.284624 -2.202578 -2.881903 0.134620 5.810900 9.025986\n10214 32.622060 1.311630 -2.298155 -2.889427 0.328484 5.736230 9.012404\n10215 32.628192 1.322390 -2.456089 -2.902571 0.446437 5.375204 9.042236\n10216 32.634257 1.310147 -2.518463 -2.910251 0.362442 5.133040 8.984804\n10217 32.640077 1.261259 -2.611499 -2.930708 0.145553 4.632729 8.717307\n10218 32.646319 1.229412 -2.642635 -2.942382 0.162998 4.446142 8.589159\n10219 32.652305 1.167944 -2.677491 -2.959719 0.536314 4.393992 8.436109\n10220 32.658445 1.144988 -2.684118 -2.963916 0.780437 4.458247 8.351318\n10221 32.664440 1.106055 -2.691641 -2.968970 1.137538 4.443704 8.074126\n10222 32.670451 1.082447 -2.702980 -2.970460 1.192403 4.401703 7.904867\n10223 32.676443 1.049543 -2.736894 -2.966082 1.141822 4.610740 7.682193\n10224 32.682438 1.037295 -2.762106 -2.956625 1.080356 4.839119 7.630878\n10225 32.688549 1.017149 -2.831263 -2.913797 0.778103 5.255760 7.492311\n10226 32.694568 1.010819 -2.873823 -2.881860 0.583989 5.370576 7.441683\n10227 32.700820 1.001737 -2.970781 -2.808874 0.193340 5.375061 7.518174\n10228 32.706526 0.999453 -3.022516 -2.772773 0.034684 5.295167 7.628337\n10229 32.712679 1.007385 -3.123864 -2.710241 0.035557 5.140447 7.831081\n10230 32.718638 1.018691 -3.171254 -2.683843 0.223332 5.079780 7.871877\n10231 32.724653 1.060366 -3.258430 -2.635066 0.897743 5.020848 7.725804\n10232 32.730794 1.090981 -3.297203 -2.611519 1.252920 5.016245 7.633584\n10233 32.736772 1.179214 -3.364724 -2.568693 1.807162 5.064265 7.416506\n10234 32.742899 1.236504 -3.391568 -2.550682 2.077841 5.074004 7.268961\n10235 32.748903 1.366919 -3.433725 -2.520455 2.593383 5.185325 6.965139\n10236 32.755023 1.431423 -3.448398 -2.505087 2.815525 5.385512 6.708696\n10237 32.761044 1.547408 -3.461668 -2.464068 3.045361 6.040482 6.199107\n10238 32.767149 1.590507 -3.459007 -2.435992 3.024668 6.425768 5.967385\n10239 32.773041 1.657803 -3.429248 -2.371536 2.892420 7.228240 5.611918\n10240 32.779217 1.675563 -3.403780 -2.338932 2.797290 7.575493 5.456289\n10241 32.785150 1.671062 -3.338801 -2.282070 2.680115 7.985392 5.133078\n10242 32.791149 1.649669 -3.301001 -2.258891 2.656969 8.067948 4.972252\n10243 32.797380 1.588456 -3.214724 -2.221764 2.558766 8.251400 4.872587\n10244 32.803767 1.552302 -3.165913 -2.206568 2.491323 8.317695 4.937702\n10245 32.809398 1.470561 -3.058527 -2.182146 2.387383 8.274788 5.071704\n10246 32.815858 1.376477 -2.947784 -2.166003 2.444715 7.941142 4.978860\n10247 32.821523 1.327063 -2.895308 -2.161550 2.507916 7.703859 4.900105\n10248 32.827900 1.226063 -2.800192 -2.157654 2.634277 7.222886 4.922145\n10249 32.833621 1.180296 -2.757161 -2.155365 2.720502 7.021118 5.010273\n10250 32.839923 1.106261 -2.673656 -2.140164 2.885157 6.843440 5.316933\n10251 32.845618 1.079132 -2.631460 -2.124526 2.925061 6.876533 5.474410\n10252 32.851853 1.041515 -2.538280 -2.081273 2.876147 7.092686 5.604589\n10253 32.857635 1.033596 -2.487166 -2.056783 2.780368 7.192200 5.609082\n10254 32.863893 1.039015 -2.377553 -2.009041 2.537264 7.301191 5.547283\n10255 32.869693 1.062131 -2.322634 -1.987258 2.455528 7.369174 5.538054\n10256 32.875975 1.159191 -2.224746 -1.942340 2.493193 7.543421 5.568936\n10257 32.881808 1.227877 -2.187690 -1.914843 2.638339 7.617110 5.581717\n10258 32.888084 1.385980 -2.143266 -1.845277 3.073512 7.686965 5.442355\n10259 32.893849 1.464733 -2.134960 -1.805078 3.259274 7.683271 5.347314\n10260 32.900071 1.605790 -2.139370 -1.721472 3.491498 7.608908 5.085273\n10261 32.905812 1.660177 -2.146888 -1.681634 3.556347 7.644051 4.888234\n10262 32.911998 1.749256 -2.166334 -1.602955 3.473846 7.895820 4.485794\n10263 32.918115 1.783113 -2.173249 -1.563007 3.374795 8.064597 4.160703\n10264 32.924084 1.825149 -2.172270 -1.480616 3.093851 8.565181 3.558601\n10265 32.930101 1.832518 -2.163995 -1.436930 2.940018 8.822693 3.277944\n10266 32.936161 1.805938 -2.121438 -1.350691 2.748471 9.245561 2.826226\n10267 32.942194 1.778764 -2.088485 -1.311754 2.674265 9.430214 2.663238\n10268 32.948389 1.694983 -1.995529 -1.238713 2.546753 9.805176 2.424629\n10269 32.954371 1.645897 -1.937045 -1.204083 2.476886 9.931842 2.314062\n10270 32.960377 1.533607 -1.798139 -1.133315 2.346928 10.009379 2.025789\n10271 32.966605 1.473991 -1.721567 -1.092787 2.253557 9.940644 1.873636\n10272 32.972557 1.340474 -1.557451 -0.998249 2.265676 9.717517 1.586118\n10273 32.978478 1.274949 -1.468367 -0.945952 2.383962 9.678057 1.549915\n10274 32.984604 1.140975 -1.269876 -0.827632 2.690153 9.760094 1.268453\n10275 32.990547 1.074577 -1.163282 -0.763189 2.838897 9.886170 1.026576\n10276 32.996666 0.963560 -0.920572 -0.632470 2.880790 10.363584 0.554073\n10277 33.002703 0.917178 -0.778467 -0.567950 2.865694 10.661849 0.390581\n10278 33.008776 0.828898 -0.456082 -0.441595 3.099051 11.187073 -0.084442\n10279 33.014666 0.784245 -0.277034 -0.377257 3.203217 11.391631 -0.238408\n10280 33.020879 0.684163 0.099044 -0.240803 3.291530 11.547351 -0.324760\n10281 33.026830 0.621331 0.292728 -0.169512 3.308150 11.509509 -0.308305\n10282 33.032972 0.466159 0.675837 -0.009743 2.978268 11.177892 -0.047976\n10283 33.038940 0.373182 0.857671 0.082169 2.702467 10.900814 0.146586\n10284 33.044954 0.149767 1.226752 0.309702 2.032939 10.260489 0.850579\n10285 33.051100 0.075403 1.334419 0.393352 1.838459 10.114952 1.129408\n10286 33.057066 -0.115197 1.581281 0.634243 1.630450 9.906717 1.825067\n10287 33.063150 -0.198056 1.684877 0.757662 1.616975 9.894590 2.069395\n10288 33.068994 -0.317366 1.849784 0.999532 1.683909 9.929230 2.363069\n10289 33.075133 -0.351950 1.907509 1.112168 1.823998 9.951687 2.439295\n10290 33.081026 -0.358584 1.976747 1.308410 2.230776 10.117094 2.544566\n10291 33.087185 -0.323907 1.993838 1.413396 2.482039 10.243754 2.602079\n10292 33.093314 -0.243748 1.999270 1.539125 2.679448 10.293855 2.571753\n10293 33.099389 -0.189870 2.000052 1.601774 2.669492 10.268804 2.539153\n10294 33.105355 -0.078166 2.009834 1.726823 2.587430 10.233027 2.524788\n10295 33.111358 -0.046064 2.018872 1.764641 2.601368 10.229577 2.569033\n10296 33.117359 0.025381 2.062037 1.857463 2.650049 10.282295 2.717105\n10297 33.123318 0.053018 2.094448 1.900888 2.618418 10.313653 2.797126\n10298 33.129521 0.105535 2.189959 1.990738 2.517246 10.276501 2.922473\n10299 33.135482 0.122412 2.226824 2.018557 2.510277 10.228086 2.970438\n10300 33.141556 0.167141 2.321901 2.089216 2.637112 10.116750 2.989938\n10301 33.147519 0.193360 2.361253 2.122555 2.745012 10.065269 2.953153\n10302 33.153600 0.251459 2.413457 2.183979 2.915243 9.858978 3.000171\n10303 33.159555 0.289120 2.420043 2.210338 2.989003 9.693139 3.222748\n10304 33.165666 0.379999 2.386527 2.251707 3.125036 9.349779 3.973897\n10305 33.171772 0.444198 2.331021 2.270153 3.214829 9.179788 4.497790\n10306 33.177899 0.528998 2.206812 2.290488 3.401464 8.934237 5.023242\n10307 33.183900 0.570773 2.113537 2.301480 3.489035 8.824809 5.205629\n10308 33.189921 0.647824 1.884030 2.325033 3.525967 8.819184 5.554228\n10309 33.195867 0.711884 1.715950 2.336952 3.479379 8.941199 5.838701\n10310 33.201905 0.836025 1.458538 2.341376 3.402070 8.909368 6.057683\n10311 33.207936 0.924430 1.299080 2.335306 3.426502 8.704193 6.073789\n10312 33.214163 1.177191 0.906424 2.301838 3.798743 8.169367 6.000790\n10313 33.220053 1.317623 0.725545 2.283207 4.060925 8.095602 6.003851\n10314 33.226197 1.629534 0.372231 2.250770 4.491630 8.069450 5.892777\n10315 33.232889 1.956914 0.044104 2.219712 4.591299 7.774269 5.372233\n10316 33.238373 2.123594 -0.101838 2.197308 4.560854 7.518067 5.084011\n10317 33.244744 2.436741 -0.340353 2.132698 4.446714 7.192537 4.634377\n10318 33.250471 2.575889 -0.427032 2.095448 4.314007 7.228526 4.378940\n10319 33.256813 2.790042 -0.526342 2.027112 3.993766 7.569447 3.570522\n10320 33.262367 2.860025 -0.542523 1.999499 3.853446 7.728229 3.146959\n10321 33.268737 2.917856 -0.518478 1.957753 3.728691 7.801460 2.544970\n10322 33.274305 2.911524 -0.481741 1.939928 3.772284 7.693444 2.425809\n10323 33.280757 2.848323 -0.374951 1.905152 4.034429 7.401648 2.328748\n10324 33.286579 2.796959 -0.309155 1.891307 4.226932 7.333959 2.266155\n10325 33.292982 2.670553 -0.156045 1.880098 4.654814 7.432512 1.996561\n10326 33.298613 2.600740 -0.070546 1.883968 4.859304 7.499329 1.784719\n10327 33.304875 2.469093 0.111251 1.906162 5.277991 7.586602 1.192374\n10328 33.310680 2.415636 0.206286 1.917137 5.489053 7.670431 0.888708\n10329 33.316923 2.343593 0.405572 1.923799 5.859012 7.896923 0.412708\n10330 33.322796 2.325935 0.512154 1.917622 6.051672 7.976377 0.228394\n10331 33.328892 2.319486 0.746883 1.895529 6.286563 8.190309 -0.117325\n10332 33.334921 2.323775 0.878082 1.885211 6.298938 8.390074 -0.291586\n10333 33.340969 2.340674 1.165181 1.872614 6.312478 8.968261 -0.571619\n10334 33.347059 2.354736 1.316074 1.868849 6.299114 9.285625 -0.679852\n10335 33.353091 2.395925 1.612056 1.852187 6.263990 9.721135 -0.705638\n10336 33.359202 2.424333 1.748971 1.833160 6.270993 9.794243 -0.601348\n10337 33.365309 2.493996 1.995616 1.775719 6.227383 9.481283 -0.335372\n10338 33.371201 2.529520 2.104532 1.743973 6.200309 9.164606 -0.176334\n10339 33.377199 2.582466 2.295561 1.688213 6.144485 8.598488 0.193074\n10340 33.383116 2.597770 2.380382 1.668689 6.074045 8.375029 0.409809\n10341 33.389317 2.609027 2.530226 1.642301 5.979073 7.840899 0.898855\n10342 33.395290 2.605443 2.593441 1.629351 5.996981 7.566679 1.119846\n10343 33.401402 2.583153 2.693273 1.602798 6.036671 7.259619 1.453141\n10344 33.407403 2.564814 2.730022 1.594010 6.047538 7.229173 1.584786\n10345 33.413554 2.506813 2.778866 1.602716 6.018721 7.334229 1.817187\n10346 33.419461 2.466517 2.791709 1.628311 5.921805 7.478057 1.919564\n10347 33.425565 2.378497 2.788913 1.727025 5.590003 7.880838 2.117708\n10348 33.431757 2.334318 2.770341 1.794999 5.434196 8.002425 2.256387\n10349 33.437652 2.253202 2.694126 1.950701 5.313169 7.841624 2.644597\n10350 33.443550 2.220126 2.636889 2.033274 5.385493 7.646694 2.868607\n10351 33.449662 2.168631 2.488477 2.203091 5.706593 7.269072 3.317333\n10352 33.455579 2.151265 2.401584 2.294019 5.914470 7.050292 3.542922\n10353 33.461725 2.147637 2.219201 2.492532 6.332353 6.337160 4.091485\n10354 33.468092 2.163956 2.132271 2.594144 6.405639 5.993319 4.294123\n10355 33.473750 2.242807 1.978377 2.776525 6.210986 5.866447 4.148894\n10356 33.479857 2.305640 1.912326 2.849356 6.073077 5.968698 3.864386\n10357 33.485951 2.475074 1.807251 2.952403 6.115894 5.964224 3.276241\n10358 33.491826 2.580746 1.769917 2.985484 6.306324 6.003830 2.959756\n10359 33.498155 2.817932 1.723133 3.034473 6.719882 6.537554 2.132300\n10360 33.503993 2.938018 1.713838 3.058462 6.930303 6.821853 1.674954\n10361 33.510147 3.144272 1.723750 3.108442 7.359766 6.903141 0.951075\n10362 33.516060 3.221378 1.740897 3.129774 7.571116 6.708673 0.753954\n10363 33.522172 3.306563 1.793410 3.147545 7.985399 6.175898 0.708539\n10364 33.528147 3.312798 1.828790 3.142750 8.164944 5.962075 0.797714\n10365 33.534318 3.249572 1.919123 3.121062 8.382895 5.652221 0.893434\n10366 33.540338 3.184309 1.973118 3.106571 8.415152 5.529170 0.809188\n10367 33.546221 3.002233 2.090556 3.064324 8.505838 4.896087 0.661729\n10368 33.552347 2.896629 2.149174 3.031971 8.672778 4.444087 0.725552\n10369 33.558449 2.678882 2.263596 2.940600 9.197820 3.820519 1.034675\n10370 33.564527 2.578341 2.318217 2.885217 9.384613 3.755552 1.166325\n10371 33.570601 2.407820 2.420127 2.762923 9.364624 3.869688 1.238721\n10372 33.576566 2.340361 2.467352 2.696747 9.183850 3.918984 1.231779\n10373 33.582577 2.245645 2.554277 2.562900 8.703160 3.787232 1.231874\n10374 33.588650 2.220279 2.591650 2.497860 8.489204 3.643287 1.299269\n10375 33.594635 2.213908 2.648805 2.373466 8.177094 3.462670 1.602952\n10376 33.601194 2.225996 2.669527 2.315482 8.062609 3.469390 1.752838\n10377 33.606727 2.257693 2.697631 2.214308 7.890891 3.466431 1.992475\n10378 33.612651 2.270267 2.704859 2.172757 7.820199 3.467646 2.087142\n10379 33.618727 2.281041 2.706033 2.108190 7.688327 3.589487 2.307769\n10380 33.625373 2.279814 2.698704 2.085007 7.654785 3.620521 2.450080\n10381 33.631111 2.265087 2.665223 2.054247 7.659942 3.429061 2.703679\n10382 33.637480 2.241086 2.605747 2.040984 7.711878 3.178097 2.918675\n10383 33.643160 2.224271 2.567310 2.039807 7.757548 3.122398 3.001976\n10384 33.649498 2.181583 2.476622 2.044052 7.917697 3.008734 3.087609\n10385 33.655100 2.154002 2.425711 2.047899 8.000795 2.878288 3.088987\n10386 33.661634 2.089387 2.311261 2.054986 8.114150 2.510844 3.045360\n10387 33.667157 2.054960 2.250315 2.055995 8.170751 2.306961 3.045022\n10388 33.673781 1.985211 2.133864 2.051740 8.432462 1.926142 3.073669\n10389 33.679209 1.944830 2.082375 2.047776 8.638555 1.806092 3.009697\n10390 33.685600 1.853868 2.001724 2.038216 9.097615 1.742510 2.735088\n10391 33.691268 1.807636 1.975099 2.030840 9.299453 1.684098 2.628712\n10392 33.697743 1.717534 1.948518 2.004308 9.609490 1.467390 2.605547\n10393 33.703388 1.678959 1.948048 1.984454 9.732548 1.431641 2.666960\n10394 33.709772 1.633529 1.970535 1.934188 9.990165 1.472153 3.002211\n10395 33.715353 1.628847 1.990279 1.905403 10.113789 1.407745 3.179204\n10396 33.721713 1.651152 2.038263 1.841826 10.175511 1.171245 3.413792\n10397 33.727465 1.679239 2.063376 1.807205 10.118305 1.058696 3.461096\n10398 33.733853 1.758834 2.113608 1.735425 9.934087 0.893023 3.546799\n10399 33.739560 1.808738 2.137169 1.700167 9.815892 0.871155 3.619701\n10400 33.745892 1.929069 2.177011 1.632029 9.522915 0.923793 3.738443\n10401 33.751610 1.993983 2.191709 1.597834 9.349590 0.926256 3.769769\n10402 33.757910 2.109633 2.206685 1.537473 9.077845 0.783264 3.864817\n10403 33.764017 2.151389 2.206747 1.514829 9.017925 0.693841 3.975215\n10404 33.770073 2.193269 2.193015 1.481095 9.011038 0.585213 4.264349\n10405 33.775908 2.191829 2.179459 1.469746 9.082553 0.568285 4.411239\n10406 33.781825 2.142031 2.135056 1.452715 9.394445 0.529218 4.599512\n10407 33.787826 2.106143 2.111474 1.446759 9.543981 0.530824 4.651477\n10408 33.794077 2.021423 2.064001 1.433694 9.723338 0.665687 4.722106\n10409 33.799918 1.977101 2.044777 1.427751 9.686965 0.738674 4.707038\n10410 33.806123 1.888226 2.025066 1.422500 9.512506 0.809417 4.690691\n10411 33.811978 1.845360 2.026412 1.424806 9.406038 0.844766 4.695072\n10412 33.818231 1.773575 2.059541 1.441710 9.099209 0.911561 4.756067\n10413 33.824048 1.749157 2.090570 1.456230 8.903708 0.876821 4.818847\n10414 33.830336 1.708778 2.175383 1.498635 8.444552 0.739959 4.989357\n10415 33.836065 1.691973 2.225880 1.525098 8.212861 0.715407 5.087699\n10416 33.842355 1.666788 2.330992 1.587495 7.846052 0.797779 5.367395\n10417 33.848272 1.661106 2.380255 1.624383 7.775703 0.961639 5.522137\n10418 33.854374 1.677463 2.460241 1.709269 7.767181 1.260453 5.836939\n10419 33.860337 1.697325 2.487040 1.754792 7.745574 1.230099 5.977373\n10420 33.866342 1.756196 2.507603 1.843909 7.650403 1.072122 6.166408\n10421 33.872434 1.797656 2.502418 1.886574 7.597519 1.073883 6.209111\n10422 33.878419 1.906304 2.467931 1.971313 7.521392 1.117210 6.307226\n10423 33.884532 1.968099 2.439423 2.013013 7.522828 1.096526 6.384540\n10424 33.890428 2.094604 2.362344 2.088100 7.605723 1.090840 6.606129\n10425 33.896711 2.155680 2.315890 2.119286 7.665906 1.131311 6.738659\n10426 33.902672 2.268107 2.212728 2.169440 7.682309 1.108035 6.991722\n10427 33.908626 2.311357 2.157165 2.191820 7.616861 1.026868 7.132451\n10428 33.914760 2.367950 2.036915 2.236790 7.370723 0.823646 7.474069\n10429 33.920752 2.383341 1.971865 2.261806 7.236042 0.742906 7.679793\n10430 33.926970 2.384814 1.829634 2.315456 7.072606 0.725700 8.002718\n10431 33.932927 2.372168 1.751755 2.341217 7.041728 0.826438 8.057858\n10432 33.939055 2.323879 1.580632 2.379284 6.981175 1.048773 8.005938\n10433 33.944997 2.285115 1.485575 2.387545 6.930483 1.097198 7.943027\n10434 33.951057 2.196173 1.271758 2.378530 6.891667 0.939689 7.970155\n10435 33.956982 2.146584 1.157142 2.362405 6.938168 0.756769 8.123744\n10436 33.963065 2.030510 0.919181 2.314134 7.085918 0.408123 8.467180\n10437 33.968918 1.965020 0.796181 2.283013 7.169936 0.296684 8.614254\n10438 33.975105 1.814801 0.550720 2.202487 7.246374 0.105764 8.732777\n10439 33.981099 1.734415 0.430739 2.152172 7.210531 0.040667 8.730871\n10440 33.987195 1.568961 0.201554 2.030171 7.026172 0.021699 8.597920\n10441 33.993346 1.490915 0.098331 1.960519 6.875896 0.036970 8.470047\n10442 33.999343 1.352423 -0.078597 1.812677 6.473873 -0.032810 8.191132\n10443 34.005397 1.301705 -0.150946 1.737992 6.263202 -0.119235 7.975863\n10444 34.011237 1.213840 -0.250723 1.581288 5.710814 -0.385461 8.062721\n10445 34.017334 1.150899 -0.280864 1.495798 5.376828 -0.610911 8.375948\n10446 34.023507 1.073277 -0.302529 1.306278 5.163145 -1.004660 8.594663\n10447 34.029645 1.054267 -0.299573 1.208644 5.256167 -1.088220 8.704949\n10448 34.035429 1.006179 -0.298859 1.017914 5.497651 -1.169536 8.663826\n10449 34.041560 0.989397 -0.300169 0.925700 5.674367 -1.093350 8.473116\n10450 34.047660 0.991493 -0.309671 0.749274 6.186188 -0.820428 8.185540\n10451 34.053715 0.999774 -0.320540 0.663604 6.429771 -0.682317 7.975107\n10452 34.059971 1.003319 -0.343150 0.500871 6.853940 -0.282011 7.554932\n10453 34.065721 0.993013 -0.352693 0.428390 7.061780 -0.057276 7.398243\n10454 34.071810 0.947366 -0.362947 0.305127 7.377832 0.364633 7.059483\n10455 34.077829 0.912192 -0.360714 0.252992 7.443263 0.514644 6.938913\n10456 34.083929 0.806530 -0.347898 0.159228 7.478168 0.623793 6.816555\n10457 34.089828 0.736361 -0.339643 0.113376 7.462695 0.608032 6.771634\n10458 34.095944 0.567978 -0.323908 0.020885 7.431505 0.547601 6.817630\n10459 34.101983 0.469908 -0.318533 -0.025266 7.424199 0.481714 6.856884\n10460 34.108188 0.258152 -0.314050 -0.118264 7.404153 0.403577 6.865795\n10461 34.114550 0.045310 -0.320178 -0.215286 7.408967 0.375707 6.854673\n10462 34.120169 -0.054201 -0.327490 -0.268023 7.407968 0.320635 6.900373\n10463 34.126661 -0.254329 -0.349420 -0.402556 7.444634 0.142730 7.102594\n10464 34.132261 -0.334502 -0.361072 -0.466963 7.501107 0.060152 7.132552\n10465 34.138617 -0.483335 -0.389018 -0.594160 7.706366 0.004686 7.062514\n10466 34.144344 -0.553850 -0.405908 -0.651371 7.820783 0.065455 7.023808\n10467 34.150863 -0.687124 -0.447052 -0.748388 7.957146 0.257121 6.932315\n10468 34.156431 -0.748590 -0.473306 -0.790031 8.002101 0.323326 6.882851\n10469 34.163015 -0.860612 -0.539825 -0.870228 8.125851 0.381440 6.817874\n10470 34.168567 -0.911407 -0.578791 -0.911885 8.202546 0.372950 6.821504\n10471 34.174928 -1.009709 -0.662638 -0.998676 8.327840 0.320143 6.852345\n10472 34.180570 -1.058946 -0.704829 -1.042919 8.352305 0.299259 6.844839\n10473 34.186693 -1.156139 -0.780804 -1.133382 8.310140 0.233111 6.817846\n10474 34.192656 -1.201687 -0.812143 -1.179934 8.255448 0.149763 6.809580\n10475 34.198862 -1.277990 -0.857222 -1.279396 8.123993 -0.024926 6.841540\n10476 34.204710 -1.308962 -0.870504 -1.333452 8.079123 -0.033735 6.889238\n10477 34.210900 -1.362249 -0.878115 -1.445540 7.955467 0.089472 6.836435\n10478 34.216713 -1.387959 -0.872722 -1.499956 7.841672 0.196017 6.728392\n10479 34.223042 -1.449450 -0.849561 -1.598330 7.527639 0.431488 6.390359\n10480 34.228918 -1.486608 -0.834690 -1.641076 7.380433 0.556250 6.211712\n10481 34.234942 -1.560816 -0.807943 -1.717020 7.252977 0.675270 6.051810\n10482 34.240889 -1.592773 -0.800154 -1.752335 7.272295 0.658080 6.070277\n10483 34.247212 -1.643900 -0.801167 -1.819700 7.422437 0.621298 6.240049\n10484 34.253231 -1.666731 -0.808603 -1.850523 7.531544 0.637615 6.333483\n10485 34.259014 -1.714539 -0.829842 -1.901721 7.724047 0.800051 6.450262\n10486 34.265137 -1.736215 -0.842967 -1.921740 7.810996 0.935415 6.483989\n10487 34.271258 -1.760613 -0.878652 -1.956484 7.947381 1.285258 6.588406\n10488 34.277369 -1.759079 -0.902435 -1.972944 7.902036 1.445666 6.566813\n10489 34.283256 -1.723014 -0.965421 -2.005201 7.621266 1.772719 6.206838\n10490 34.289284 -1.694844 -1.005101 -2.019616 7.463235 1.964093 5.887300\n10491 34.295386 -1.637108 -1.093366 -2.037426 7.307412 2.342149 5.260864\n10492 34.301414 -1.615737 -1.138458 -2.040762 7.357496 2.494503 5.107028\n10493 34.307408 -1.605514 -1.221368 -2.046925 7.546961 2.617321 5.184938\n10494 34.313527 -1.618337 -1.255584 -2.053159 7.592650 2.515853 5.342483\n10495 34.319568 -1.686553 -1.306636 -2.074836 7.585738 2.020170 5.694738\n10496 34.325561 -1.742175 -1.322649 -2.090128 7.573496 1.755828 5.840364\n10497 34.331719 -1.886134 -1.333289 -2.122699 7.570990 1.349197 5.989143\n10498 34.337660 -1.967990 -1.327368 -2.138294 7.593235 1.123724 6.038173\n10499 34.343779 -2.131123 -1.294668 -2.171606 7.750424 0.493994 6.162213\n10500 34.349843 -2.205935 -1.268548 -2.191113 7.880885 0.213886 6.183088\n10501 34.355846 -2.328821 -1.201417 -2.231208 8.245468 0.105528 6.016890\n10502 34.361933 -2.376266 -1.162751 -2.249458 8.413706 0.299420 5.856570\n10503 34.367926 -2.444342 -1.076916 -2.277922 8.514879 0.861442 5.465586\n10504 34.373821 -2.468104 -1.032560 -2.289813 8.446124 1.067001 5.271842\n10505 34.379900 -2.503129 -0.950047 -2.315990 8.181908 1.241647 4.920455\n10506 34.385939 -2.520197 -0.913334 -2.331461 8.045850 1.311813 4.799441\n10507 34.392049 -2.569556 -0.851083 -2.364956 7.860235 1.555381 4.672299\n10508 34.398029 -2.603750 -0.826418 -2.381542 7.822871 1.686946 4.680412\n10509 34.404133 -2.693335 -0.790942 -2.418341 7.789065 1.856427 4.955348\n10510 34.410110 -2.748113 -0.781211 -2.442222 7.722183 1.868860 5.153672\n10511 34.416125 -2.872475 -0.783514 -2.507348 7.409495 1.859374 5.608296\n10512 34.422321 -2.938237 -0.797335 -2.548295 7.209816 1.813456 5.823061\n10513 34.428408 -3.065328 -0.853977 -2.645890 6.835731 1.604799 6.292157\n10514 34.434312 -3.121507 -0.898687 -2.700454 6.735784 1.446606 6.531425\n10515 34.440337 -3.205360 -1.019547 -2.815323 6.743795 1.123204 6.945296\n10516 34.446311 -3.232802 -1.092978 -2.871979 6.820750 1.051218 7.065484\n10517 34.452327 -3.265552 -1.253063 -2.976903 6.965095 1.151872 7.011157\n10518 34.458409 -3.274522 -1.334474 -3.025983 7.017755 1.297168 6.848261\n10519 34.464398 -3.283445 -1.487768 -3.118168 7.101668 1.708912 6.424895\n10520 34.470416 -3.287550 -1.555024 -3.159608 7.116639 1.940663 6.198668\n10521 34.476571 -3.302438 -1.661801 -3.227282 7.086446 2.446029 5.782215\n10522 34.482505 -3.314801 -1.698337 -3.251169 7.060941 2.730891 5.602511\n10523 34.488820 -3.344604 -1.735008 -3.276819 7.077376 3.270862 5.424107\n10524 34.494827 -3.363784 -1.735862 -3.279876 7.117527 3.463407 5.372535\n10525 34.500837 -3.407810 -1.708447 -3.271989 7.089847 3.564673 5.391940\n10526 34.506913 -3.422108 -1.689524 -3.264965 7.005056 3.488500 5.533893\n10527 34.512843 -3.418308 -1.654876 -3.251122 6.831221 3.189449 6.016851\n10528 34.519422 -3.362935 -1.642285 -3.237142 6.816687 2.705950 6.401877\n10529 34.525042 -3.316560 -1.651198 -3.228665 6.914138 2.448139 6.476383\n10530 34.531472 -3.195641 -1.696689 -3.206009 7.225143 2.252043 6.217190\n10531 34.536957 -3.124237 -1.729184 -3.190330 7.370793 2.382029 5.945832\n10532 34.543528 -2.965999 -1.799953 -3.149450 7.669086 2.922971 5.417789\n10533 34.549149 -2.878128 -1.830186 -3.125875 7.794959 3.245378 5.262440\n10534 34.555488 -2.693234 -1.864108 -3.073359 7.873064 3.954685 5.024990\n10535 34.561385 -2.603916 -1.865259 -3.042800 7.821007 4.251816 4.865127\n10536 34.567608 -2.447960 -1.833449 -2.966906 7.605497 4.663423 4.486125\n10537 34.573336 -2.385874 -1.799883 -2.918217 7.481287 4.773512 4.385814\n10538 34.579657 -2.300333 -1.712689 -2.807369 7.266834 4.879816 4.343689\n10539 34.585372 -2.272659 -1.666654 -2.753255 7.229248 4.821222 4.429285\n10540 34.591599 -2.234617 -1.588030 -2.664511 7.353293 4.213332 4.673402\n10541 34.597535 -2.225536 -1.559552 -2.631963 7.512802 3.714625 4.744849\n10542 34.603613 -2.233268 -1.529566 -2.586238 7.863670 2.935520 4.782386\n10543 34.609454 -2.245880 -1.526718 -2.568451 8.011646 2.773510 4.810065\n10544 34.615842 -2.279244 -1.533331 -2.535398 8.099864 2.786354 4.991846\n10545 34.621593 -2.297678 -1.543286 -2.523891 8.047185 2.861884 5.114479\n10546 34.627932 -2.316382 -1.572011 -2.526714 7.932858 3.089351 5.302663\n10547 34.633554 -2.310353 -1.587934 -2.541982 7.909536 3.357643 5.291297\n10548 34.639851 -2.271380 -1.617993 -2.585551 7.883471 4.193182 5.041672\n10549 34.645773 -2.236665 -1.626641 -2.603750 7.835702 4.696866 4.857097\n10550 34.651837 -2.139919 -1.625000 -2.615992 7.610266 5.501603 4.576605\n10551 34.657824 -2.082611 -1.617153 -2.608846 7.477996 5.695483 4.510737\n10552 34.663928 -1.957690 -1.592968 -2.578421 7.284827 5.736660 4.523722\n10553 34.669853 -1.891822 -1.577450 -2.556170 7.286635 5.568257 4.509007\n10554 34.675979 -1.774858 -1.551754 -2.501283 7.507163 5.161024 4.334970\n10555 34.681933 -1.727252 -1.544367 -2.470057 7.721538 4.958803 4.167335\n10556 34.688057 -1.652939 -1.541724 -2.395544 8.395394 4.388346 3.890697\n10557 34.694356 -1.629056 -1.547794 -2.354201 8.770640 4.071738 3.790340\n10558 34.700106 -1.603841 -1.571880 -2.280643 9.372503 3.569253 3.640289\n10559 34.706168 -1.600902 -1.589243 -2.255454 9.525492 3.443576 3.612201\n10560 34.712272 -1.615692 -1.629292 -2.240030 9.533244 3.460207 3.645168\n10561 34.718331 -1.633476 -1.648800 -2.251762 9.429871 3.630419 3.676171\n10562 34.724312 -1.687703 -1.678908 -2.309125 9.089348 4.319638 3.675135\n10563 34.730339 -1.722214 -1.686022 -2.351516 8.890742 4.737970 3.641480\n10564 34.736377 -1.802025 -1.678633 -2.458193 8.531452 5.389917 3.560748\n10565 34.742461 -1.846994 -1.663279 -2.519889 8.350534 5.553222 3.531314\n10566 34.748587 -1.949149 -1.611738 -2.654236 7.925281 5.691646 3.601922\n10567 34.754546 -2.005911 -1.578112 -2.724249 7.700054 5.724815 3.688194\n10568 34.760684 -2.125567 -1.501800 -2.853437 7.325827 5.820470 3.796375\n10569 34.766621 -2.184232 -1.457324 -2.900060 7.198978 5.830229 3.867313\n10570 34.772647 -2.286451 -1.342315 -2.944140 7.043340 5.777588 4.134166\n10571 34.778731 -2.324285 -1.276338 -2.947008 6.945159 5.984458 4.140649\n10572 34.784798 -2.368026 -1.153551 -2.927634 6.783930 6.342852 4.076297\n10573 34.790798 -2.374996 -1.104230 -2.914242 6.902447 6.380718 4.081162\n10574 34.796747 -2.343464 -1.041118 -2.895414 7.251258 6.493647 4.015448\n10575 34.802702 -2.317708 -1.030141 -2.888220 7.379835 6.559168 3.976266\n10576 34.808922 -2.246713 -1.037663 -2.877615 7.712809 6.470337 3.769214\n10577 34.815080 -2.206720 -1.053718 -2.877052 7.840572 6.356802 3.751268\n10578 34.820922 -2.131073 -1.102991 -2.886092 7.745212 6.189998 3.746327\n10579 34.827268 -2.096546 -1.128483 -2.899679 7.574510 6.151234 3.831685\n10580 34.832979 -2.052667 -1.173816 -2.943843 7.001080 6.071053 4.270370\n10581 34.839177 -2.045544 -1.191012 -2.967995 6.671037 6.029714 4.511969\n10582 34.845172 -2.058108 -1.210688 -3.013080 6.255068 5.995358 5.053846\n10583 34.851332 -2.081763 -1.219135 -3.033596 6.162045 6.010777 5.270796\n10584 34.857301 -2.149721 -1.242159 -3.069853 6.088808 6.039623 5.546839\n10585 34.863253 -2.195338 -1.259200 -3.092566 6.039383 6.070482 5.752512\n10586 34.869382 -2.308911 -1.307631 -3.165113 5.632178 6.175221 6.077616\n10587 34.875343 -2.368877 -1.337416 -3.218521 5.339550 6.183887 6.151527\n10588 34.881446 -2.491879 -1.409271 -3.361026 4.824608 6.056356 6.212341\n10589 34.887439 -2.554737 -1.449517 -3.444774 4.598402 5.993464 6.179393\n10590 34.893473 -2.662104 -1.532224 -3.617420 4.362379 5.996688 6.122711\n10591 34.899980 -2.701048 -1.572022 -3.702785 4.339574 6.035090 6.123427\n10592 34.905559 -2.746632 -1.632683 -3.864166 4.243280 6.169516 6.128627\n10593 34.912182 -2.751631 -1.654679 -4.007320 4.070467 6.283602 6.104881\n10594 34.917843 -2.741728 -1.652948 -4.072509 3.964528 6.325605 6.142716\n10595 34.924218 -2.699939 -1.634162 -4.183003 3.814701 6.417593 6.313235\n10596 34.929734 -2.667049 -1.623316 -4.224640 3.802886 6.449100 6.417111\n10597 34.936200 -2.581677 -1.611334 -4.276036 3.787651 6.492968 6.630797\n10598 34.941701 -2.533862 -1.612412 -4.287626 3.747039 6.513506 6.714293\n10599 34.948209 -2.443933 -1.629415 -4.297180 3.616620 6.477756 6.743281\n10600 34.953893 -2.404027 -1.645954 -4.301919 3.570652 6.350142 6.724318\n10601 34.960396 -2.335711 -1.689558 -4.315648 3.555498 6.128542 6.681758\n10602 34.965983 -2.306248 -1.712510 -4.322169 3.500686 6.152644 6.692488\n10603 34.972275 -2.274370 -1.758615 -4.328806 3.125149 6.507844 6.754065\n10604 34.978032 -2.278290 -1.778057 -4.327790 2.903676 6.639335 6.779997\n10605 34.984403 -2.324957 -1.822366 -4.328461 2.553262 6.640924 6.843168\n10606 34.990136 -2.372149 -1.852214 -4.335841 2.431755 6.574190 6.894674\n10607 34.996446 -2.499127 -1.932675 -4.368955 2.278507 6.490469 6.925269\n10608 35.002157 -2.565420 -1.978115 -4.390769 2.240543 6.525784 6.896670\n10609 35.008361 -2.682451 -2.067295 -4.427244 2.226310 6.858396 6.760069\n10610 35.014411 -2.726336 -2.105658 -4.437132 2.274569 7.071321 6.669258\n10611 35.020550 -2.769010 -2.157400 -4.442268 2.279496 7.523169 6.496812\n10612 35.026333 -2.774806 -2.169917 -4.439826 2.173210 7.686986 6.465826\n10613 35.032617 -2.764755 -2.169834 -4.428171 1.842587 7.753101 6.410723\n10614 35.038633 -2.749524 -2.157369 -4.417831 1.739882 7.708608 6.384230\n10615 35.044473 -2.694789 -2.122742 -4.375093 1.833937 7.670645 6.301695\n10616 35.050513 -2.654201 -2.103376 -4.338170 2.009062 7.641558 6.238663\n10617 35.056677 -2.548305 -2.059325 -4.234020 2.357056 7.506766 6.154299\n10618 35.062527 -2.489958 -2.033601 -4.171642 2.401913 7.420295 6.087149\n10619 35.068722 -2.373548 -1.973109 -4.039363 2.248944 7.374750 5.932701\n10620 35.074502 -2.317173 -1.936726 -3.971123 2.117171 7.448320 5.899235\n10621 35.080735 -2.206877 -1.847988 -3.822469 1.781486 7.753540 5.994924\n10622 35.086682 -2.153238 -1.795867 -3.737143 1.568185 8.005415 6.118603\n10623 35.092858 -2.051697 -1.686493 -3.542278 1.150632 8.362141 6.394037\n10624 35.098861 -2.008899 -1.635470 -3.437917 1.034038 8.298226 6.484766\n10625 35.104803 -1.956820 -1.558208 -3.232475 1.109117 7.818984 6.599488\n10626 35.110856 -1.953178 -1.533248 -3.134990 1.278182 7.484832 6.696199\n10627 35.116857 -1.998112 -1.504291 -2.957455 1.611869 6.921255 6.799762\n10628 35.123107 -2.037186 -1.498420 -2.875010 1.689519 6.750142 6.753988\n10629 35.129027 -2.126875 -1.498950 -2.713660 1.731194 6.581934 6.614677\n10630 35.135037 -2.168415 -1.502131 -2.634465 1.736604 6.564640 6.610635\n10631 35.141114 -2.230184 -1.507041 -2.484899 1.733608 6.688373 6.717581\n10632 35.147066 -2.246738 -1.506559 -2.415936 1.749954 6.843554 6.815838\n10633 35.153168 -2.243260 -1.489230 -2.286298 1.779687 7.147427 6.953084\n10634 35.159229 -2.220172 -1.464651 -2.220244 1.717787 7.214209 7.024598\n10635 35.165434 -2.134883 -1.375025 -2.074075 1.397100 7.180446 7.060696\n10636 35.171397 -2.071045 -1.309840 -1.991577 1.200348 7.091156 7.089349\n10637 35.177505 -1.901691 -1.145609 -1.807004 0.934774 6.782398 7.328563\n10638 35.183431 -1.802456 -1.053093 -1.708168 0.917732 6.596333 7.486363\n10639 35.189556 -1.607994 -0.867309 -1.511600 1.059611 6.235319 7.791044\n10640 35.195375 -1.522243 -0.779502 -1.416411 1.151793 6.073902 7.890896\n10641 35.201559 -1.375526 -0.620759 -1.230588 1.312186 5.736153 8.009595\n10642 35.207685 -1.311184 -0.551924 -1.138949 1.356796 5.569322 8.060344\n10643 35.213675 -1.183983 -0.433360 -0.957775 1.390918 5.347403 8.113770\n10644 35.219657 -1.114224 -0.382049 -0.869674 1.401611 5.312075 8.141788\n10645 35.225918 -0.958748 -0.289298 -0.703070 1.408862 5.278799 8.144214\n10646 35.231744 -0.876878 -0.244322 -0.622814 1.370279 5.245838 8.158960\n10647 35.237813 -0.710156 -0.153708 -0.454599 1.125183 5.203509 8.263367\n10648 35.243797 -0.622880 -0.107868 -0.360443 0.947878 5.236538 8.358297\n10649 35.249915 -0.432908 -0.022681 -0.141293 0.679609 5.408176 8.572604\n10650 35.255872 -0.328730 0.013460 -0.015226 0.634993 5.569129 8.677664\n10651 35.261815 -0.106291 0.066081 0.257559 0.684175 6.024302 8.821366\n10652 35.267923 0.007222 0.081056 0.395679 0.759685 6.225122 8.852156\n10653 35.274039 0.217804 0.093393 0.658650 0.928347 6.395761 8.847758\n10654 35.280100 0.310973 0.094394 0.780181 0.961892 6.415777 8.862252\n10655 35.285985 0.479261 0.098077 1.003462 0.899059 6.402331 9.007271\n10656 35.292204 0.561766 0.104289 1.106882 0.825549 6.356481 9.125192\n10657 35.298285 0.733253 0.126564 1.298640 0.664055 6.068981 9.372576\n10658 35.304154 0.821296 0.141734 1.385915 0.572053 5.853206 9.483455\n10659 35.310243 0.991484 0.176340 1.537542 0.337952 5.455725 9.628690\n10660 35.316255 1.070536 0.194239 1.602501 0.253216 5.341533 9.618620\n10661 35.322352 1.226377 0.226451 1.715308 0.296168 5.343186 9.506619\n10662 35.328802 1.310275 0.239824 1.767105 0.373287 5.411454 9.481672\n10663 35.334421 1.505005 0.261154 1.866957 0.386811 5.487919 9.477073\n10664 35.340793 1.737929 0.274741 1.959495 0.147490 5.364819 9.427904\n10665 35.346530 1.866166 0.277966 2.003284 0.069051 5.265814 9.390395\n10666 35.353043 2.131431 0.278490 2.089177 0.183299 5.257682 9.378580\n10667 35.358637 2.261148 0.274644 2.133020 0.375232 5.344339 9.381360\n10668 35.364943 2.503628 0.253625 2.225099 0.952572 5.588519 9.409134\n10669 35.370635 2.617422 0.236594 2.272857 1.228338 5.698899 9.380486\n10670 35.377002 2.834920 0.198934 2.369050 1.497803 5.777446 9.178647\n10671 35.382755 2.937513 0.182512 2.415895 1.476723 5.735916 9.035302\n10672 35.388972 3.124706 0.166048 2.509127 1.341910 5.624064 8.754022\n10673 35.394951 3.209842 0.168973 2.557623 1.318323 5.668846 8.590816\n10674 35.400944 3.371267 0.195388 2.661953 1.414512 6.108037 8.147419\n10675 35.406751 3.449301 0.217471 2.717782 1.541760 6.467066 7.907755\n10676 35.413122 3.592969 0.276723 2.831849 1.900589 7.239628 7.764141\n10677 35.419093 3.660740 0.314773 2.889608 2.046721 7.549803 7.788754\n10678 35.425194 3.808492 0.412895 3.008358 2.004452 7.964214 7.727098\n10679 35.431084 3.884549 0.470653 3.070316 1.803558 8.145370 7.704893\n10680 35.437052 4.055412 0.610227 3.218642 1.148228 8.489738 7.727676\n10681 35.443106 4.130548 0.670844 3.286634 0.976064 8.511260 7.890316\n10682 35.449175 4.275849 0.760626 3.412387 1.088321 8.218961 8.152583\n10683 35.455136 4.345459 0.779571 3.465325 1.352485 7.942849 8.208241\n10684 35.461249 4.466815 0.757461 3.545899 2.065031 7.404596 8.368447\n10685 35.467314 4.513106 0.721080 3.573074 2.348921 7.212780 8.485045\n10686 35.473454 4.585405 0.614962 3.604681 2.506366 6.926919 8.621475\n10687 35.479301 4.612453 0.553524 3.610209 2.423733 6.839207 8.590532\n10688 35.485353 4.641196 0.427851 3.600755 2.199753 6.844087 8.355337\n10689 35.491450 4.640172 0.367899 3.587801 2.179945 6.912638 8.145370\n10690 35.497469 4.611063 0.261857 3.549715 2.434769 7.083929 7.620239\n10691 35.503531 4.590760 0.215995 3.525244 2.615429 7.176904 7.261071\n10692 35.509519 4.563647 0.138147 3.472635 3.062166 7.323742 6.451619\n10693 35.515498 4.559381 0.106843 3.449551 3.349161 7.363846 6.094874\n10694 35.521639 4.566419 0.062637 3.415202 3.994255 7.302413 5.677749\n10695 35.527708 4.571418 0.051754 3.401736 4.359307 7.176729 5.515319\n10696 35.533615 4.569839 0.053647 3.376135 5.023800 6.815289 5.052158\n10697 35.539765 4.558299 0.065122 3.362968 5.287524 6.631100 4.789429\n10698 35.545783 4.513874 0.113731 3.334403 5.581996 6.464097 4.322054\n10699 35.551895 4.488440 0.152673 3.319857 5.579226 6.525901 4.094755\n10700 35.557941 4.447834 0.253545 3.292489 5.380882 6.733224 3.644370\n10701 35.563809 4.443398 0.309621 3.278026 5.310687 6.751963 3.477809\n10702 35.569871 4.449310 0.425023 3.247228 5.311548 6.772177 3.319104\n10703 35.575977 4.456779 0.477129 3.230630 5.450902 6.799018 3.286826\n10704 35.582008 4.473944 0.559843 3.197324 6.000002 6.801448 3.139501\n10705 35.587995 4.485775 0.587319 3.181908 6.288396 6.721112 3.032165\n10706 35.594199 4.533585 0.610444 3.148827 6.639510 6.396876 2.553546\n10707 35.600130 4.566061 0.608182 3.128843 6.821112 6.252779 2.297854\n10708 35.606196 4.645378 0.581285 3.078289 7.339586 6.041225 1.810258\n10709 35.612121 4.688054 0.564643 3.048622 7.609700 5.907691 1.570560\n10710 35.618266 4.772335 0.539073 2.976686 7.891600 5.479751 1.298401\n10711 35.624390 4.805834 0.534000 2.934970 7.823500 5.226879 1.177171\n10712 35.630358 4.862191 0.543531 2.845856 7.342188 4.889851 0.866353\n10713 35.636408 4.887753 0.555786 2.801766 7.074726 4.851617 0.745944\n10714 35.642350 4.945629 0.588451 2.727551 6.688052 5.060608 0.603451\n10715 35.648576 4.980010 0.608156 2.702330 6.565133 5.230271 0.590133\n10716 35.654466 5.045127 0.646293 2.679226 6.477992 5.406245 0.570400\n10717 35.660589 5.063273 0.662846 2.682500 6.560227 5.417675 0.586276\n10718 35.666455 5.062083 0.692013 2.721966 7.099747 5.458926 0.819583\n10719 35.672579 5.039934 0.705300 2.756714 7.475862 5.511505 0.968969\n10720 35.678619 4.963783 0.726137 2.849250 8.278996 5.541769 1.200616\n10721 35.684618 4.914450 0.729807 2.903416 8.558082 5.471104 1.232171\n10722 35.690768 4.812437 0.724257 3.012590 8.484314 5.279056 1.048901\n10723 35.696712 4.759509 0.714974 3.059972 8.265738 5.157229 0.917883\n10724 35.702867 4.653536 0.681251 3.132004 7.969871 4.711733 0.654295\n10725 35.708828 4.606059 0.658672 3.157151 7.972778 4.399505 0.553714\n10726 35.715089 4.530017 0.601775 3.184751 8.240187 3.746677 0.501904\n10727 35.721889 4.504455 0.568430 3.188045 8.427607 3.422921 0.472049\n10728 35.726974 4.485310 0.498691 3.178549 8.799630 2.781057 0.426896\n10729 35.732985 4.493081 0.462710 3.165866 8.950516 2.461990 0.416683\n10730 35.739031 4.546485 0.390754 3.126409 9.072124 1.969352 0.376650\n10731 35.745025 4.591796 0.357204 3.101376 9.060556 1.821072 0.343486\n10732 35.751169 4.712336 0.298046 3.045665 8.961240 1.556300 0.335545\n10733 35.757912 4.873127 0.253772 2.990929 8.892276 1.342806 0.381956\n10734 35.763450 4.967285 0.239731 2.966592 8.861488 1.290770 0.392592\n10735 35.769719 5.175958 0.230328 2.928131 8.786034 1.301265 0.205699\n10736 35.775260 5.285122 0.235913 2.915519 8.735970 1.262189 -0.000508\n10737 35.781908 5.498234 0.259763 2.899071 8.659310 0.983100 -0.503079\n10738 35.787471 5.597014 0.274542 2.891421 8.620574 0.795180 -0.784436\n10739 35.793837 5.777991 0.304911 2.870574 8.508869 0.382642 -1.401010\n10740 35.799494 5.857857 0.319436 2.856908 8.460686 0.167007 -1.672688\n10741 35.806038 5.980506 0.350303 2.822609 8.478467 -0.243730 -1.981891\n10742 35.811661 6.022234 0.369087 2.802429 8.510170 -0.430924 -2.056328\n10743 35.818177 6.058707 0.411749 2.753829 8.629272 -0.776067 -2.224885\n10744 35.823789 6.048677 0.434269 2.724333 8.693005 -0.959982 -2.286130\n10745 35.829961 5.980717 0.480406 2.656940 8.660008 -1.392916 -2.261039\n10746 35.835753 5.931079 0.505041 2.619200 8.636765 -1.602262 -2.199754\n10747 35.842112 5.810920 0.555528 2.539518 8.676632 -1.875768 -2.054787\n10748 35.847948 5.745050 0.580502 2.501535 8.734838 -2.009042 -2.014572\n10749 35.853967 5.612015 0.631989 2.433514 8.866676 -2.271949 -2.014684\n10750 35.859913 5.546322 0.657745 2.400796 8.872082 -2.369254 -1.998525\n10751 35.866101 5.417939 0.705374 2.331573 8.843562 -2.534841 -1.921581\n10752 35.872005 5.357682 0.727666 2.294516 8.842767 -2.580391 -1.850320\n10753 35.878174 5.247983 0.770783 2.219668 8.850842 -2.660772 -1.597621\n10754 35.884045 5.201582 0.791217 2.184473 8.862632 -2.752548 -1.452760\n10755 35.890336 5.127051 0.837446 2.124198 8.904488 -2.974045 -1.069914\n10756 35.896099 5.096682 0.865262 2.101195 8.933432 -3.079729 -0.849271\n10757 35.902373 5.043978 0.936668 2.072522 8.916857 -3.080668 -0.615263\n10758 35.908222 5.024177 0.980917 2.065669 8.828395 -2.985594 -0.572550\n10759 35.914357 5.002780 1.074283 2.059650 8.535006 -2.951686 -0.503455\n10760 35.920361 5.004049 1.119141 2.057452 8.415675 -3.052063 -0.441570\n10761 35.926458 5.030109 1.194482 2.056080 8.303659 -3.320517 -0.222090\n10762 35.932457 5.053723 1.219682 2.059112 8.304828 -3.447388 -0.120394\n10763 35.938552 5.121440 1.235841 2.075308 8.248376 -3.785236 0.222407\n10764 35.944524 5.161689 1.224781 2.087837 8.223640 -3.994907 0.547509\n10765 35.950583 5.232443 1.163603 2.116657 8.307288 -4.335584 1.111462\n10766 35.956743 5.261045 1.113691 2.131180 8.428856 -4.489402 1.270394\n10767 35.962691 5.295648 0.976355 2.157648 8.795262 -4.895111 1.429890\n10768 35.968801 5.300515 0.894643 2.168331 8.929725 -5.198843 1.507574\n10769 35.974771 5.292389 0.726190 2.185672 9.053687 -5.862950 1.678623\n10770 35.980799 5.280288 0.648740 2.193869 9.055741 -6.116497 1.733314\n10771 35.986747 5.240526 0.523939 2.213844 8.955470 -6.421251 1.722295\n10772 35.992880 5.213492 0.478203 2.224788 8.909324 -6.489203 1.729340\n10773 35.998997 5.155090 0.418328 2.241112 8.879265 -6.439402 1.893801\n10774 36.004822 5.126820 0.401838 2.243106 8.888631 -6.343120 1.965997\n10775 36.011026 5.100946 0.385908 2.233764 8.935237 -5.988373 2.042393\n10776 36.016916 5.103269 0.384471 2.225525 8.895484 -5.851563 1.989167\n10777 36.023244 5.141143 0.386730 2.208318 8.683452 -5.613656 1.750854\n10778 36.028965 5.174410 0.387367 2.200350 8.571219 -5.489573 1.666972\n10779 36.035096 5.252842 0.390498 2.181920 8.478414 -5.323810 1.859368\n10780 36.041170 5.290405 0.390926 2.167952 8.500717 -5.331470 2.136016\n10781 36.047143 5.347436 0.386854 2.120743 8.578224 -5.430690 2.629710\n10782 36.053241 5.366783 0.381673 2.087033 8.534889 -5.441743 2.840423\n10783 36.059262 5.389011 0.366168 2.003440 8.109240 -5.535936 3.142711\n10784 36.065295 5.400568 0.366828 1.947368 7.682796 -5.559399 3.203427\n10785 36.071346 5.297414 0.390392 1.824836 7.151585 -5.507090 3.996123\n10786 36.077330 5.260304 0.412361 1.754991 7.107330 -5.611432 3.909704\n10787 36.083283 5.143170 0.476316 1.601764 7.098595 -6.205074 4.470514\n10788 36.089503 5.042213 0.499686 1.517997 7.058394 -6.507015 4.864204\n10789 36.095493 4.832821 0.558400 1.345488 6.996428 -6.694289 5.026824\n10790 36.101519 4.730222 0.596048 1.263104 7.045331 -6.641609 5.344949\n10791 36.107502 4.477639 0.658785 1.106049 7.045365 -6.470822 5.628852\n10792 36.113588 4.347208 0.692444 1.029479 7.078645 -6.354885 5.518305\n10793 36.119708 4.087340 0.741188 0.870082 7.276241 -6.232874 5.617761\n10794 36.125654 3.947459 0.744995 0.785762 7.319758 -6.162642 5.529461\n10795 36.131861 3.688825 0.729337 0.614681 7.294028 -5.775697 5.330992\n10796 36.137782 3.568598 0.707390 0.534040 7.252239 -5.532854 5.389496\n10797 36.144066 3.317193 0.637817 0.395121 7.140832 -5.146793 5.323286\n10798 36.149852 3.193585 0.597884 0.338250 7.132184 -4.969625 5.370886\n10799 36.156090 2.943452 0.504968 0.247271 7.184983 -4.658065 5.789447\n10800 36.162592 2.817006 0.456531 0.210158 7.169512 -4.550413 5.926402\n10801 36.167907 2.557293 0.360819 0.150881 6.943481 -4.183796 6.014638\n10802 36.174589 2.451938 0.323477 0.140244 6.770738 -3.882012 5.894351\n10803 36.180132 2.266919 0.267794 0.154610 6.447022 -3.112888 5.461369\n10804 36.186722 2.105854 0.234545 0.211645 6.363533 -2.686654 5.269428\n10805 36.192225 2.032098 0.226283 0.250246 6.409523 -2.658331 5.227446\n10806 36.198895 1.898047 0.235144 0.334840 6.539680 -2.717997 5.312651\n10807 36.204285 1.830962 0.253884 0.381331 6.476757 -2.779518 5.324486\n10808 36.210852 1.702321 0.328048 0.485489 6.357742 -2.934754 5.257532\n10809 36.216518 1.648478 0.384605 0.540725 6.419391 -2.991210 5.324209\n10810 36.223324 1.557531 0.529540 0.650892 6.567213 -3.212988 5.557307\n10811 36.229470 1.528656 0.609707 0.696944 6.636121 -3.415679 5.669711\n10812 36.235172 1.506236 0.766361 0.751005 6.620356 -3.866415 5.940170\n10813 36.240626 1.509462 0.840178 0.760910 6.555361 -3.999446 6.089008\n10814 36.246906 1.547180 0.973745 0.756688 6.547635 -4.059110 6.427692\n10815 36.252741 1.583392 1.031611 0.744376 6.622405 -3.989991 6.641956\n10816 36.259019 1.686913 1.119137 0.707778 6.713459 -3.996682 7.132159\n10817 36.264775 1.754154 1.145376 0.682200 6.698939 -4.112202 7.333446\n10818 36.271048 1.914456 1.159110 0.608125 6.459016 -4.390263 7.609106\n10819 36.276755 2.000214 1.150010 0.563705 6.279472 -4.459292 7.708578\n10820 36.283162 2.170068 1.115094 0.474952 6.156155 -4.431060 7.928805\n10821 36.288757 2.250635 1.093438 0.435098 6.170058 -4.378892 8.068326\n10822 36.294995 2.400386 1.042019 0.371493 6.190087 -4.235859 8.286962\n10823 36.300905 2.471002 1.011783 0.344745 6.222432 -4.109416 8.323267\n10824 36.307141 2.603452 0.941351 0.292990 6.334918 -3.753536 8.245809\n10825 36.312909 2.664031 0.902832 0.269627 6.387204 -3.530600 8.104413\n10826 36.318994 2.769793 0.830494 0.229342 6.456820 -2.868878 7.476377\n10827 36.324999 2.811695 0.800064 0.213205 6.444069 -2.442584 7.025715\n10828 36.331058 2.865849 0.756869 0.192109 6.377663 -1.778398 6.344624\n10829 36.337116 2.875073 0.748265 0.183583 6.313615 -1.620929 6.267552\n10830 36.343128 2.852460 0.763920 0.157924 6.072123 -1.512135 6.653050\n10831 36.349232 2.817539 0.789967 0.138809 5.885517 -1.546032 6.984696\n10832 36.355287 2.685568 0.884526 0.089065 5.412077 -1.789159 7.717257\n10833 36.361275 2.588324 0.949998 0.059881 5.146810 -1.931700 8.111149\n10834 36.367298 2.343580 1.106074 -0.004435 4.707902 -2.091382 8.830024\n10835 36.373267 2.207739 1.187774 -0.039789 4.611256 -2.115828 9.141789\n10836 36.379345 1.936456 1.334941 -0.120066 4.603257 -2.094922 9.500392\n10837 36.385289 1.813011 1.395466 -0.166337 4.595190 -2.057988 9.590123\n10838 36.391333 1.598025 1.484650 -0.270998 4.547344 -1.905738 9.628751\n10839 36.397455 1.504688 1.513910 -0.327845 4.606958 -1.779923 9.556070\n10840 36.403464 1.348910 1.547306 -0.439068 4.783062 -1.581409 9.454754\n10841 36.409429 1.284414 1.551832 -0.493588 4.906455 -1.573558 9.390483\n10842 36.415841 1.193069 1.537152 -0.609162 5.018067 -1.857485 9.243347\n10843 36.421696 1.169714 1.518572 -0.669594 5.018021 -2.013732 9.211670\n10844 36.427900 1.163409 1.465813 -0.788302 5.091438 -2.045476 9.076990\n10845 36.433714 1.178343 1.435286 -0.841763 5.140575 -1.940062 8.887410\n10846 36.439754 1.240449 1.367666 -0.919399 5.052003 -1.605762 8.600739\n10847 36.445729 1.277085 1.329195 -0.946756 5.001359 -1.316191 8.514224\n10848 36.451878 1.363016 1.246323 -0.986226 4.774225 -0.505788 8.478404\n10849 36.457867 1.412474 1.203346 -0.995502 4.580024 -0.091921 8.563663\n10850 36.463910 1.509403 1.120982 -0.998441 4.300903 0.580854 8.701409\n10851 36.469954 1.553283 1.080515 -0.992823 4.283953 0.891809 8.693381\n10852 36.475906 1.628666 0.999916 -0.953751 4.554344 1.251083 8.677834\n10853 36.481978 1.655480 0.960694 -0.923101 4.810463 1.254938 8.700034\n10854 36.488074 1.677298 0.882563 -0.857357 5.196757 0.967961 9.082119\n10855 36.494088 1.675466 0.838386 -0.827504 5.406153 0.750208 9.478233\n10856 36.500137 1.679238 0.743937 -0.778430 5.706228 0.840300 9.815565\n10857 36.506199 1.678222 0.693835 -0.753461 5.531107 1.115580 9.602223\n10858 36.512254 1.637149 0.574378 -0.694238 5.025125 1.414611 8.558886\n10859 36.518312 1.615266 0.511149 -0.662410 4.894745 1.410550 8.044430\n10860 36.524346 1.601684 0.397413 -0.597106 5.002606 1.390361 7.817049\n10861 36.530383 1.605802 0.347137 -0.567711 5.228035 1.364254 7.911238\n10862 36.536509 1.623569 0.274751 -0.515614 5.617475 1.357874 7.913320\n10863 36.542366 1.628974 0.254466 -0.486715 5.741863 1.469905 7.875496\n10864 36.548509 1.606148 0.235209 -0.426413 6.041450 1.950003 7.773104\n10865 36.554736 1.578031 0.235553 -0.393996 6.169411 2.276688 7.857493\n10866 36.560771 1.540349 0.246192 -0.360707 5.969852 2.540068 8.031058\n10867 36.566624 1.527416 0.249499 -0.358940 5.637268 2.626636 8.009558\n10868 36.572693 1.501692 0.247296 -0.381524 4.929635 2.846917 7.805249\n10869 36.578766 1.483548 0.245957 -0.395109 4.771307 2.930874 7.730222\n10870 36.584754 1.423551 0.253234 -0.412367 4.749499 3.157603 7.813659\n10871 36.590911 1.379068 0.265793 -0.410928 4.537680 3.253353 7.956358\n10872 36.596878 1.258095 0.303949 -0.387983 4.141834 3.279587 8.175582\n10873 36.602996 1.189047 0.320351 -0.369668 4.162862 3.192786 8.222172\n10874 36.608900 1.051790 0.334117 -0.310376 4.572558 2.986827 8.255735\n10875 36.615071 0.989285 0.332363 -0.271574 4.881519 2.975202 8.266485\n10876 36.621126 0.880543 0.319809 -0.191711 5.275581 3.198722 8.127958\n10877 36.627127 0.833492 0.313717 -0.154202 5.329368 3.319824 7.939703\n10878 36.633055 0.747712 0.307221 -0.108061 5.276787 3.330245 7.517109\n10879 36.639075 0.707147 0.306370 -0.109547 5.183866 3.312825 7.402306\n10880 36.645393 0.636518 0.310888 -0.160781 4.941531 3.369454 7.517611\n10881 36.651797 0.574223 0.321331 -0.257695 4.803413 3.461082 7.860487\n10882 36.657422 0.539952 0.325626 -0.311872 4.747701 3.553599 7.960704\n10883 36.663595 0.449229 0.325238 -0.409481 4.706927 3.780169 7.982007\n10884 36.669447 0.387113 0.320413 -0.450914 4.680572 3.808018 8.015631\n10885 36.675797 0.237567 0.306078 -0.517435 4.540187 3.732716 8.231467\n10886 36.681415 0.158553 0.299391 -0.545142 4.495131 3.679908 8.352384\n10887 36.688004 0.005032 0.288263 -0.600972 4.647579 3.647016 8.443469\n10888 36.693669 -0.067466 0.283400 -0.630608 4.700602 3.647244 8.376835\n10889 36.699916 -0.198976 0.273752 -0.698469 4.598762 3.570110 8.256078\n10890 36.705669 -0.260582 0.267998 -0.742310 4.449690 3.537880 8.251971\n10891 36.711896 -0.375326 0.245387 -0.853325 4.163694 3.536428 8.371650\n10892 36.717796 -0.433327 0.224305 -0.917952 4.112501 3.484523 8.427666\n10893 36.723704 -0.555998 0.155173 -1.061923 4.125473 3.215081 8.586492\n10894 36.729675 -0.624679 0.106179 -1.137748 4.147995 3.135788 8.658008\n10895 36.735848 -0.781217 -0.013961 -1.285610 4.208009 3.307341 8.682209\n10896 36.741918 -0.870791 -0.082965 -1.356262 4.229635 3.381859 8.710863\n10897 36.747818 -1.081258 -0.225610 -1.491343 4.211588 3.334189 8.806871\n10898 36.753832 -1.198996 -0.293711 -1.557382 4.148110 3.302684 8.862757\n10899 36.759936 -1.455069 -0.415117 -1.690631 3.876203 3.383996 8.888390\n10900 36.765962 -1.592327 -0.465437 -1.756375 3.711256 3.489752 8.834952\n10901 36.772079 -1.875867 -0.542764 -1.883305 3.276650 3.635065 8.803977\n10902 36.778181 -2.015254 -0.569228 -1.945303 2.988045 3.564222 8.973196\n10903 36.784049 -2.277217 -0.603011 -2.071603 2.547240 3.225671 9.843411\n10904 36.790168 -2.397475 -0.612375 -2.135903 2.466192 3.106079 10.336770\n10905 36.796218 -2.614994 -0.629118 -2.259163 2.486101 2.820553 10.910031\n10906 36.802204 -2.716945 -0.643073 -2.317366 2.553998 2.586365 10.928066\n10907 36.808175 -2.904949 -0.694798 -2.436438 2.660468 2.062083 10.680912\n10908 36.814296 -2.980226 -0.732002 -2.498370 2.670696 1.762432 10.552549\n10909 36.820670 -3.080485 -0.824437 -2.628425 2.687284 1.249444 10.430031\n10910 36.826425 -3.112760 -0.876730 -2.696503 2.659384 1.140100 10.366886\n10911 36.832568 -3.167155 -0.981599 -2.831911 2.379035 1.030195 10.171127\n10912 36.838513 -3.202305 -1.030132 -2.898777 2.185190 0.919599 10.192723\n10913 36.844675 -3.288465 -1.116865 -3.031803 1.752773 0.925570 11.138272\n10914 36.850586 -3.335416 -1.158589 -3.093796 1.506969 1.098625 11.868217\n10915 36.856797 -3.455552 -1.250383 -3.210452 1.018250 1.183824 12.749877\n10916 36.862651 -3.522218 -1.311164 -3.266848 0.824034 0.964016 12.815673\n10917 36.868644 -3.663039 -1.462458 -3.370681 0.874153 0.690333 12.498388\n10918 36.874803 -3.725496 -1.549199 -3.418659 1.086752 0.825670 12.446080\n10919 36.880769 -3.832067 -1.743602 -3.509332 1.327420 1.104042 12.469019\n10920 36.886865 -3.873718 -1.845530 -3.555831 1.336034 1.084942 12.358488\n10921 36.892898 -3.938244 -2.049449 -3.671417 1.343592 1.031886 11.958076\n10922 36.898990 -3.971324 -2.149298 -3.740594 1.410290 1.118905 11.714022\n10923 36.904922 -4.051269 -2.331084 -3.891779 1.900334 1.414044 11.406774\n10924 36.911011 -4.095237 -2.409401 -3.973323 2.257830 1.441292 11.242271\n10925 36.916982 -4.182039 -2.539845 -4.146095 2.707047 1.032687 10.562780\n10926 36.923035 -4.227563 -2.594573 -4.239194 2.861224 0.644705 10.164859\n10927 36.928961 -4.337460 -2.681181 -4.440250 3.179289 -0.144844 9.508294\n10928 36.935107 -4.402911 -2.707785 -4.539153 3.272172 -0.485958 9.329525\n10929 36.941115 -4.558802 -2.715700 -4.715662 3.333273 -1.154701 9.371154\n10930 36.947119 -4.646544 -2.694208 -4.791546 3.335662 -1.435879 9.543893\n10931 36.953360 -4.818599 -2.602726 -4.911304 3.310666 -1.732531 10.080205\n10932 36.959231 -4.893776 -2.538956 -4.953435 3.269845 -1.767770 10.307214\n10933 36.965354 -5.010917 -2.398132 -5.013332 3.073060 -1.714036 10.541522\n10934 36.971325 -5.050568 -2.316912 -5.039347 3.012597 -1.574837 10.574137\n10935 36.977358 -5.054009 -2.225319 -5.069874 3.302700 -1.317701 10.620245\n10936 36.983439 -5.036870 -2.205015 -5.084697 3.525626 -1.268809 10.566347\n10937 36.989506 -4.970143 -2.231250 -5.114832 3.860165 -1.238178 10.349437\n10938 36.995520 -4.928529 -2.279255 -5.133199 4.057239 -1.246973 10.224677\n10939 37.001658 -4.843320 -2.431602 -5.176102 4.495983 -1.187894 9.991673\n10940 37.007776 -4.801119 -2.529049 -5.196158 4.733410 -1.120445 9.935498\n10941 37.013626 -4.715423 -2.748344 -5.233090 5.110706 -1.172750 10.094324\n10942 37.020202 -4.675196 -2.860045 -5.249887 5.171626 -1.287407 10.192943\n10943 37.025797 -4.596169 -3.067868 -5.272849 5.293527 -1.413597 10.242940\n10944 37.031895 -4.558087 -3.155843 -5.276695 5.337939 -1.421160 10.116776\n10945 37.037853 -4.478069 -3.286287 -5.263388 5.204752 -1.245737 9.641099\n10946 37.044396 -4.427134 -3.331741 -5.248503 5.140066 -1.107772 9.425260\n10947 37.049904 -4.297299 -3.394659 -5.208748 4.907683 -0.780759 8.908155\n10948 37.056506 -4.138442 -3.431459 -5.163205 5.032197 -0.316249 8.303610\n10949 37.062011 -4.054455 -3.444659 -5.139927 5.235797 -0.031216 7.977600\n10950 37.068543 -3.912825 -3.458406 -5.092376 5.788030 0.507216 7.243845\n10951 37.074087 -3.853747 -3.465104 -5.072700 6.117908 0.657100 6.990680\n10952 37.080479 -3.780716 -3.483787 -5.046164 6.391489 0.769900 6.450713\n10953 37.086373 -3.763133 -3.494479 -5.037416 6.361094 0.804655 6.184640\n10954 37.092480 -3.774230 -3.514593 -5.023973 6.201385 0.827501 5.720227\n10955 37.098281 -3.798270 -3.515293 -5.015635 6.158653 0.844671 5.585066\n10956 37.104514 -3.874134 -3.484232 -4.992133 6.308030 0.924692 5.471377\n10957 37.110347 -3.923846 -3.452919 -4.979297 6.447368 0.964129 5.465616\n10958 37.116671 -4.035225 -3.363040 -4.952373 6.717552 1.195258 5.429021\n10959 37.122359 -4.090069 -3.308056 -4.936710 6.806226 1.439410 5.343227\n10960 37.128652 -4.181588 -3.193087 -4.903931 6.806501 2.163430 4.944134\n10961 37.134465 -4.211274 -3.138076 -4.886769 6.745325 2.582994 4.694006\n10962 37.140483 -4.235851 -3.039066 -4.854273 6.611441 3.216704 4.187928\n10963 37.146538 -4.230837 -2.996207 -4.841071 6.611248 3.411882 3.981349\n10964 37.152640 -4.196168 -2.921445 -4.821125 6.794859 3.737765 3.700714\n10965 37.158599 -4.174222 -2.887359 -4.812587 6.926805 3.904950 3.601118\n10966 37.164626 -4.137788 -2.821679 -4.795919 7.126227 4.161070 3.445739\n10967 37.170650 -4.123322 -2.790502 -4.787729 7.112861 4.236587 3.375876\n10968 37.176890 -4.105891 -2.730051 -4.773209 6.811802 4.315424 3.279684\n10969 37.182822 -4.103838 -2.702653 -4.769271 6.638258 4.313004 3.263651\n10970 37.188900 -4.101756 -2.659520 -4.769898 6.529067 4.305628 3.452858\n10971 37.195000 -4.098084 -2.645227 -4.773026 6.526781 4.326560 3.673096\n10972 37.200870 -4.103333 -2.628686 -4.786511 6.616861 4.469042 3.947330\n10973 37.207010 -4.108267 -2.627722 -4.796205 6.612855 4.598008 4.032505\n10974 37.212903 -4.124495 -2.635224 -4.811459 6.506516 4.940827 4.155322\n10975 37.219027 -4.129791 -2.640257 -4.818845 6.409872 5.081775 4.269357\n10976 37.225050 -4.135701 -2.656158 -4.839538 6.201487 5.167383 4.473119\n10977 37.231132 -4.132582 -2.669470 -4.851108 6.156424 5.117711 4.537714\n10978 37.237352 -4.120176 -2.706021 -4.875070 6.153649 5.194558 4.541319\n10979 37.243246 -4.116935 -2.726435 -4.884871 6.149129 5.395315 4.499486\n10980 37.249246 -4.126282 -2.764733 -4.895692 6.054303 5.932841 4.311830\n10981 37.255365 -4.136983 -2.781258 -4.897669 5.978407 6.196646 4.187223\n10982 37.261339 -4.175519 -2.806908 -4.898715 5.974588 6.559173 3.892712\n10983 37.267361 -4.192102 -2.818068 -4.896854 5.985250 6.740730 3.781496\n10984 37.273356 -4.217655 -2.829201 -4.879535 5.953230 7.245932 3.466779\n10985 37.279511 -4.224536 -2.827439 -4.862517 5.871797 7.482749 3.323621\n10986 37.285622 -4.224853 -2.809448 -4.803091 5.648269 7.822860 3.134785\n10987 37.291591 -4.217450 -2.792089 -4.761031 5.570322 7.934160 3.056927\n10988 37.297709 -4.182584 -2.750089 -4.659417 5.516928 8.008975 3.075139\n10989 37.303665 -4.159408 -2.729761 -4.601783 5.554607 8.034161 3.120851\n10990 37.309697 -4.097119 -2.691922 -4.477061 5.649870 8.156004 3.211470\n10991 37.315812 -4.058187 -2.675023 -4.411420 5.650282 8.210374 3.250263\n10992 37.321809 -3.974621 -2.641959 -4.271630 5.556074 8.326198 3.167013\n10993 37.327946 -3.930949 -2.622909 -4.198182 5.475510 8.459899 3.091119\n10994 37.333817 -3.850715 -2.576485 -4.048276 5.264636 8.771942 3.087811\n10995 37.339907 -3.821541 -2.548434 -3.975052 5.158937 8.765862 3.195817\n10996 37.345902 -3.788560 -2.484947 -3.845643 5.042220 8.384058 3.547053\n10997 37.352032 -3.785589 -2.452454 -3.790830 5.048170 8.161766 3.702973\n10998 37.358011 -3.809243 -2.390721 -3.693064 5.185011 7.935301 3.745277\n10999 37.364021 -3.831923 -2.361439 -3.645471 5.247687 7.927647 3.636734\n11000 37.370031 -3.893343 -2.296825 -3.536403 5.190494 8.075700 3.350909\n11001 37.376135 -3.918768 -2.267458 -3.488671 5.123645 8.158987 3.209249\n11002 37.382103 -3.959646 -2.210777 -3.400982 4.979561 8.362770 3.137911\n11003 37.388115 -3.975438 -2.182453 -3.357728 4.923535 8.511419 3.139592\n11004 37.394170 -4.002366 -2.122773 -3.262433 4.851461 8.957582 3.239517\n11005 37.400229 -4.012107 -2.090202 -3.206453 4.804850 9.253969 3.348454\n11006 37.406365 -4.017913 -2.013571 -3.074598 4.606805 9.924071 3.533192\n11007 37.412412 -4.012227 -1.969916 -3.001968 4.453754 10.183306 3.638720\n11008 37.418489 -3.994200 -1.874568 -2.855996 4.094061 10.296299 3.897361\n11009 37.424483 -3.984440 -1.823153 -2.786225 3.949338 10.244430 4.026712\n11010 37.430524 -3.970481 -1.714272 -2.652702 3.826968 10.078963 4.266763\n11011 37.437392 -3.973723 -1.657693 -2.583504 3.825334 9.939354 4.396729\n11012 37.442655 -4.002001 -1.540893 -2.428089 3.834474 9.515534 4.707537\n11013 37.448651 -4.017988 -1.482006 -2.341165 3.851817 9.279826 4.895240\n11014 37.454663 -4.050282 -1.370154 -2.158633 3.900606 8.790103 5.293657\n11015 37.460769 -4.061717 -1.318734 -2.067750 3.948923 8.556273 5.431941\n11016 37.466888 -4.072753 -1.229802 -1.897889 4.088881 8.217024 5.579363\n11017 37.472890 -4.070903 -1.193188 -1.820626 4.144482 8.133492 5.549428\n11018 37.478998 -4.053671 -1.134977 -1.680542 4.291162 8.153587 5.546815\n11019 37.485641 -4.015885 -1.093422 -1.557379 4.316165 8.204646 5.539174\n11020 37.491144 -3.990610 -1.076357 -1.501389 4.258535 8.167154 5.662559\n11021 37.497546 -3.939806 -1.049097 -1.404908 4.027091 7.913842 6.058291\n11022 37.503020 -3.918786 -1.036214 -1.364457 3.888322 7.729768 6.296571\n11023 37.509633 -3.894145 -1.013912 -1.292097 3.725681 7.343369 6.808838\n11024 37.515103 -3.892775 -1.005515 -1.256315 3.716106 7.169334 7.062911\n11025 37.521633 -3.902533 -0.994346 -1.179760 3.805857 6.839094 7.582374\n11026 37.527236 -3.908216 -0.992955 -1.141320 3.885732 6.634851 7.791272\n11027 37.533724 -3.902894 -1.003661 -1.079425 3.979801 6.141267 7.869998\n11028 37.539261 -3.888840 -1.014686 -1.060166 4.031040 5.935609 7.807004\n11029 37.545619 -3.839248 -1.042163 -1.051533 4.224759 5.785340 7.556056\n11030 37.551355 -3.803267 -1.052785 -1.061813 4.307822 5.783364 7.441148\n11031 37.557793 -3.718585 -1.052785 -1.105000 4.324184 5.741984 7.312947\n11032 37.563391 -3.680321 -1.037846 -1.133935 4.296276 5.750448 7.339382\n11033 37.569744 -3.610844 -0.978716 -1.200901 3.927661 5.697213 7.123688\n11034 37.575539 -3.582798 -0.933100 -1.235148 3.697992 5.576964 7.072907\n11035 37.581598 -3.559739 -0.825116 -1.306571 3.497134 5.199942 7.136689\n11036 37.587604 -3.561860 -0.763113 -1.339227 3.568279 5.009618 7.112656\n11037 37.593779 -3.578331 -0.631765 -1.387831 3.946100 4.635001 7.106097\n11038 37.599750 -3.594253 -0.565941 -1.403494 4.091395 4.464627 7.047175\n11039 37.605737 -3.621790 -0.428518 -1.418774 4.151395 4.241956 6.987369\n11040 37.611719 -3.627012 -0.355576 -1.420881 4.127853 4.184510 7.066939\n11041 37.617996 -3.609454 -0.197940 -1.424269 4.064383 4.145841 7.267084\n11042 37.623856 -3.581333 -0.113486 -1.427008 4.004081 4.086163 7.373283\n11043 37.629882 -3.499718 0.062941 -1.431996 3.883777 3.871867 7.581177\n11044 37.635856 -3.450979 0.151908 -1.432534 3.833503 3.792835 7.672978\n11045 37.641944 -3.336840 0.323658 -1.422099 3.813138 3.736933 7.831172\n11046 37.647983 -3.272204 0.403051 -1.409231 3.873071 3.623755 7.861314\n11047 37.654108 -3.135136 0.543258 -1.371160 4.068300 3.270557 7.841435\n11048 37.660136 -3.069004 0.602065 -1.348188 4.170008 3.136595 7.872766\n11049 37.666100 -2.943354 0.707040 -1.299321 4.160319 2.952958 7.997411\n11050 37.672106 -2.887321 0.758171 -1.275856 4.052404 2.822095 8.133575\n11051 37.678266 -2.797429 0.865236 -1.230635 3.862961 2.621349 8.494756\n11052 37.684231 -2.779066 0.921484 -1.202769 3.949950 2.502604 8.818790\n11053 37.690358 -2.733160 1.033835 -1.138367 3.583225 2.394588 8.893910\n11054 37.696389 -2.708041 1.086398 -1.108295 3.279928 2.176597 9.013783\n11055 37.702470 -2.664811 1.165454 -1.062539 2.696559 1.718282 9.263222\n11056 37.708354 -2.635250 1.194352 -1.046736 2.547164 1.714613 9.325716\n11057 37.714483 -2.558699 1.223676 -1.024191 2.605401 1.942990 9.529799\n11058 37.720501 -2.520518 1.221165 -1.010475 2.671431 1.997650 9.473431\n11059 37.726537 -2.470497 1.198235 -0.981486 2.607820 1.909291 9.280748\n11060 37.732668 -2.454291 1.178986 -0.965852 2.528442 1.847158 9.296321\n11061 37.738660 -2.431265 1.124194 -0.935121 2.390941 1.658063 9.526844\n11062 37.744725 -2.414373 1.092752 -0.917531 2.348436 1.518737 9.688007\n11063 37.750944 -2.377712 1.019449 -0.872005 2.196842 1.154896 9.938502\n11064 37.756748 -2.366880 0.977763 -0.840452 2.100175 1.003883 9.995036\n11065 37.762752 -2.341688 0.889390 -0.758180 2.058536 0.792874 10.155149\n11066 37.768764 -2.319824 0.842719 -0.709318 2.127213 0.641818 10.336295\n11067 37.774864 -2.241247 0.739621 -0.607138 2.255861 0.244319 10.740794\n11068 37.780825 -2.174405 0.683484 -0.557415 2.281866 0.028940 10.851645\n11069 37.786964 -1.987778 0.564547 -0.463272 2.292441 -0.300122 10.801276\n11070 37.792982 -1.876795 0.504308 -0.415063 2.298161 -0.346151 10.670927\n11071 37.798915 -1.637035 0.398888 -0.306815 2.353225 -0.309453 10.445069\n11072 37.804894 -1.514056 0.359155 -0.247275 2.340039 -0.318711 10.385195\n11073 37.810989 -1.280444 0.309071 -0.125585 2.149876 -0.431362 10.250504\n11074 37.817203 -1.174480 0.296964 -0.067636 2.065273 -0.380608 10.146126\n11075 37.823078 -0.987670 0.295959 0.041569 2.060588 0.008149 9.954241\n11076 37.829220 -0.910687 0.308014 0.095466 2.073244 0.220185 9.859688\n11077 37.835240 -0.797297 0.355406 0.202995 1.934746 0.492565 9.655030\n11078 37.841401 -0.758071 0.387544 0.255022 1.760546 0.544552 9.594349\n11079 37.847495 -0.701409 0.462845 0.353671 1.456183 0.478902 9.717450\n11080 37.853396 -0.677978 0.502855 0.399145 1.394701 0.375643 9.845911\n11081 37.859286 -0.625522 0.571742 0.476985 1.396367 0.090705 10.136366\n11082 37.865341 -0.592015 0.595833 0.509814 1.423673 -0.076003 10.234279\n11083 37.871452 -0.507161 0.619213 0.566002 1.520486 -0.437174 10.353401\n11084 37.877626 -0.456781 0.617076 0.591306 1.585508 -0.638566 10.372762\n11085 37.883780 -0.345013 0.583695 0.637888 1.797005 -1.148537 10.352448\n11086 37.889626 -0.284820 0.552564 0.659990 1.928451 -1.420328 10.354793\n11087 37.895802 -0.164274 0.467849 0.702154 2.052567 -1.853596 10.419179\n11088 37.901815 -0.108129 0.419374 0.724433 2.057665 -1.991686 10.511873\n11089 37.907893 -0.007227 0.316678 0.768033 2.032188 -2.273332 10.633662\n11090 37.914324 0.036849 0.265613 0.788656 2.018664 -2.370488 10.647818\n11091 37.919858 0.115662 0.166935 0.823537 2.022579 -2.327754 10.673651\n11092 37.926370 0.156376 0.122130 0.836761 2.006248 -2.240635 10.678061\n11093 37.931792 0.250535 0.049216 0.855692 1.881000 -2.011055 10.673756\n11094 37.938286 0.356675 0.004651 0.865006 1.665248 -1.681203 10.606403\n11095 37.944028 0.410454 -0.004748 0.869790 1.595700 -1.484569 10.583293\n11096 37.950466 0.520192 0.003322 0.890449 1.360341 -1.063062 10.473428\n11097 37.956174 0.581115 0.021698 0.909853 1.168561 -0.837746 10.469289\n11098 37.962496 0.718955 0.084351 0.971468 0.640579 -0.344319 10.684734\n11099 37.968212 0.794460 0.127217 1.013386 0.515469 -0.059595 10.731165\n11100 37.974473 0.966078 0.219829 1.124692 0.567855 0.459747 10.649281\n11101 37.980170 1.058289 0.263539 1.194252 0.591048 0.680514 10.513330\n11102 37.986536 1.245333 0.344131 1.353716 0.461208 0.917769 10.357210\n11103 37.992367 1.336533 0.380218 1.440699 0.326908 0.943680 10.406415\n11104 37.998623 1.515026 0.449055 1.630579 0.160946 0.778194 10.570050\n11105 38.004410 1.600862 0.482235 1.735117 0.160890 0.613207 10.645033\n11106 38.010652 1.754196 0.535437 1.962828 0.197915 0.245791 10.709667\n11107 38.016696 1.824239 0.552938 2.084857 0.240415 0.066036 10.710343\n11108 38.022610 1.961620 0.568711 2.336407 0.286881 -0.140411 10.780166\n11109 38.028740 2.033587 0.566422 2.462278 0.268867 -0.171955 10.864037\n11110 38.034753 2.198602 0.546082 2.709026 0.141787 -0.088822 11.068189\n11111 38.040732 2.294416 0.531156 2.827528 0.014557 0.072555 11.182700\n11112 38.046759 2.508750 0.494080 3.049316 -0.254616 0.389054 11.318354\n11113 38.052642 2.621214 0.472066 3.151620 -0.324714 0.488107 11.308191\n11114 38.058864 2.838699 0.414060 3.337238 -0.277991 0.673008 11.193926\n11115 38.064682 2.938955 0.377300 3.422372 -0.212382 0.781678 11.138110\n11116 38.070839 3.137243 0.285233 3.603145 -0.210096 1.053284 11.071735\n11117 38.076880 3.192040 0.254668 3.661676 -0.292201 1.124001 11.051292\n11118 38.083083 3.298828 0.180213 3.818753 -0.615158 1.294512 11.026427\n11119 38.088925 3.330798 0.149938 3.898312 -0.755681 1.356845 11.049623\n11120 38.094904 3.358812 0.109300 4.056776 -0.911976 1.464406 11.067801\n11121 38.100989 3.360073 0.098198 4.134810 -0.931676 1.492042 11.019086\n11122 38.106957 3.357670 0.088847 4.281097 -0.974397 1.537577 10.722249\n11123 38.113229 3.370568 0.090993 4.346338 -0.943262 1.633698 10.589685\n11124 38.119091 3.398120 0.104494 4.456030 -0.609420 1.624057 10.554206\n11125 38.125239 3.417775 0.115559 4.503834 -0.329306 1.577962 10.458544\n11126 38.131281 3.465943 0.143001 4.587849 0.296925 1.534308 10.321880\n11127 38.137403 3.487782 0.157427 4.623769 0.490405 1.506407 10.202683\n11128 38.143370 3.523733 0.193617 4.686229 0.660062 1.427068 10.059312\n11129 38.149428 3.540453 0.217116 4.711389 0.694075 1.436224 10.057882\n11130 38.155366 3.585243 0.278525 4.751968 0.707171 1.680324 9.884401\n11131 38.161557 3.607056 0.316216 4.771119 0.760857 1.877972 9.801362\n11132 38.167527 3.634620 0.402336 4.814310 0.837368 2.532563 9.537305\n11133 38.173559 3.638398 0.453287 4.840349 0.819005 2.927940 9.471973\n11134 38.179511 3.629229 0.565855 4.895159 0.692997 3.541253 9.395305\n11135 38.185652 3.616207 0.627019 4.922289 0.639450 3.696764 9.368097\n11136 38.191743 3.577169 0.752862 4.975631 0.664911 3.842609 9.166127\n11137 38.197738 3.552149 0.815295 5.004685 0.773524 3.885433 8.970249\n11138 38.203726 3.485803 0.933386 5.071011 1.024242 3.905770 8.648813\n11139 38.209741 3.446975 0.988329 5.105773 1.111228 3.870819 8.540407\n11140 38.215933 3.368422 1.091143 5.161793 1.189988 3.752220 8.492804\n11141 38.221825 3.322402 1.152691 5.179774 1.209944 3.703779 8.516919\n11142 38.227827 3.269549 1.241522 5.180243 1.324639 3.736971 8.504906\n11143 38.233776 3.243805 1.294619 5.169505 1.470983 3.820355 8.479671\n11144 38.239856 3.199383 1.408075 5.137081 1.763144 4.140278 8.437361\n11145 38.246019 3.178748 1.470532 5.121372 1.844010 4.322303 8.402817\n11146 38.251990 3.133266 1.601464 5.098311 1.849241 4.516379 8.287159\n11147 38.258178 3.104763 1.666497 5.092522 1.776695 4.532912 8.176360\n11148 38.264187 3.024684 1.794449 5.091012 1.575837 4.517335 8.141437\n11149 38.270228 2.974478 1.857968 5.094064 1.439784 4.516947 8.211525\n11150 38.276115 2.847558 1.988514 5.105963 1.116985 4.516870 8.366074\n11151 38.282396 2.766978 2.054030 5.115027 0.950585 4.529310 8.503108\n11152 38.288286 2.578794 2.179185 5.134503 0.547088 4.529956 8.844413\n11153 38.294228 2.476567 2.237957 5.141415 0.384024 4.473258 9.017255\n11154 38.300286 2.265587 2.331704 5.140406 0.280838 4.242944 9.173448\n11155 38.306394 2.161927 2.364399 5.131805 0.385129 4.118935 9.125542\n11156 38.312524 1.985565 2.404781 5.101401 0.850732 3.944665 9.124861\n11157 38.318351 1.918507 2.417150 5.082664 1.090385 3.915564 9.103765\n11158 38.324550 1.830101 2.442321 5.048692 1.448811 3.943727 8.785522\n11159 38.330467 1.806965 2.463008 5.031145 1.627882 3.988210 8.489750\n11160 38.336529 1.793152 2.504773 5.012454 1.853497 4.029779 8.125432\n11161 38.342591 1.796935 2.537746 5.004383 1.980178 4.068555 8.055137\n11162 38.348778 1.824250 2.623271 4.993716 2.138511 4.226521 8.077137\n11163 38.355228 1.851191 2.677750 4.993979 2.125285 4.362456 8.067710\n11164 38.360793 1.928183 2.827983 5.015418 1.828630 4.784986 7.999884\n11165 38.367341 1.957674 2.905800 5.031909 1.575299 5.050551 8.036229\n11166 38.372773 1.985400 3.078888 5.064482 0.997341 5.583213 8.349344\n11167 38.379404 1.966638 3.259665 5.081929 0.617247 5.780249 8.590292\n11168 38.385063 1.937200 3.343974 5.083024 0.504835 5.701234 8.622786\n11169 38.391393 1.893321 3.418452 5.080278 0.419620 5.521898 8.653124\n11170 38.397025 1.789561 3.529030 5.069743 0.221966 4.916461 8.887636\n11171 38.403557 1.663404 3.589411 5.062010 -0.030661 4.235302 9.191200\n11172 38.409017 1.590185 3.601918 5.059982 -0.145326 4.049162 9.245044\n11173 38.415721 1.429187 3.599189 5.056725 -0.299562 3.916075 9.356510\n11174 38.421334 1.345152 3.589637 5.052356 -0.308966 3.866394 9.521444\n11175 38.427402 1.186211 3.566064 5.034750 -0.165177 3.732074 9.876786\n11176 38.433288 1.119734 3.553812 5.023136 -0.044132 3.654203 10.028153\n11177 38.439419 1.015473 3.535904 5.005595 0.154968 3.439131 10.139627\n11178 38.445294 0.976760 3.535353 5.003609 0.211519 3.306606 10.134134\n11179 38.451578 0.914038 3.555612 5.014349 0.216920 3.068594 10.237886\n11180 38.457494 0.887314 3.575869 5.023960 0.141918 2.975413 10.314044\n11181 38.463878 0.843324 3.633574 5.037390 -0.156143 2.905763 10.422431\n11182 38.469552 0.828977 3.664243 5.037435 -0.318904 2.920517 10.501624\n11183 38.475775 0.821108 3.718104 5.021605 -0.649301 2.919977 10.554302\n11184 38.481615 0.828916 3.737634 5.006302 -0.837598 2.897850 10.499221\n11185 38.487807 0.864127 3.745811 4.964655 -1.199749 2.795673 10.306974\n11186 38.493802 0.891730 3.732052 4.939203 -1.322525 2.696054 10.218191\n11187 38.499827 0.964712 3.669596 4.878976 -1.373875 2.464976 10.235823\n11188 38.505884 1.006168 3.620372 4.843387 -1.298637 2.358348 10.305694\n11189 38.511803 1.097529 3.490849 4.760715 -0.959232 2.195275 10.495563\n11190 38.517937 1.146380 3.414115 4.714970 -0.727462 2.138999 10.575388\n11191 38.523912 1.244531 3.245645 4.625903 -0.252492 2.085120 10.560808\n11192 38.529922 1.291091 3.159257 4.586860 -0.080562 2.061735 10.463051\n11193 38.535913 1.378708 2.993551 4.520393 0.012951 2.024300 10.175404\n11194 38.542121 1.415904 2.917281 4.491077 -0.064693 2.036814 9.986413\n11195 38.548311 1.473757 2.784294 4.433542 -0.276762 2.129270 9.638485\n11196 38.554264 1.493307 2.729641 4.403083 -0.342143 2.247132 9.524725\n11197 38.560148 1.512423 2.649418 4.337700 -0.357228 2.588685 9.348856\n11198 38.566306 1.512301 2.627731 4.304402 -0.329053 2.722507 9.273326\n11199 38.572302 1.488469 2.627333 4.238322 -0.142441 2.734111 9.122272\n11200 38.578315 1.466140 2.647198 4.205853 0.029358 2.672967 9.032736\n11201 38.584305 1.407895 2.719212 4.140088 0.499178 2.619877 8.839681\n11202 38.590297 1.379509 2.766851 4.106123 0.749436 2.641185 8.800294\n11203 38.596302 1.333228 2.881946 4.034404 1.117176 2.734997 8.909737\n11204 38.602440 1.319594 2.947927 3.996394 1.177782 2.772793 8.974302\n11205 38.608646 1.318625 3.087267 3.911442 1.131198 2.768784 9.201632\n11206 38.614640 1.330165 3.156360 3.863059 1.075226 2.708331 9.458914\n11207 38.620660 1.367149 3.283302 3.749424 0.964268 2.666079 10.117286\n11208 38.626582 1.395746 3.337315 3.683048 0.863805 2.737087 10.421455\n11209 38.632686 1.461935 3.416532 3.532355 0.569039 2.985780 10.732830\n11210 38.638761 1.497148 3.439699 3.450487 0.379494 3.089597 10.754805\n11211 38.644659 1.570573 3.448737 3.283056 -0.028584 3.165893 10.669786\n11212 38.650760 1.605990 3.432822 3.199924 -0.146229 3.110516 10.661437\n11213 38.656766 1.665816 3.357671 3.043955 -0.182431 3.012024 10.839473\n11214 38.662939 1.690141 3.299259 2.976821 -0.154081 3.001833 11.049608\n11215 38.668784 1.713890 3.143847 2.868884 -0.054977 2.740348 11.510076\n11216 38.675108 1.709257 3.045675 2.825942 -0.009519 2.484403 11.703338\n11217 38.681177 1.677324 2.805086 2.760405 0.067071 2.256727 11.994981\n11218 38.687097 1.656904 2.666394 2.736907 0.073439 2.314335 12.127567\n11219 38.693095 1.617451 2.361544 2.704691 -0.085667 2.475784 12.321581\n11220 38.699177 1.615741 2.198576 2.695884 -0.253693 2.410297 12.115664\n11221 38.705301 1.578708 1.866798 2.682932 -0.840350 2.375270 12.123820\n11222 38.711304 1.521451 1.696330 2.675500 -1.047826 2.660993 12.389962\n11223 38.717409 1.378631 1.368520 2.662557 -1.097641 3.354109 12.682766\n11224 38.725337 1.286856 1.207721 2.658919 -1.021415 3.459005 12.858472\n11225 38.729297 1.043116 0.868882 2.651348 -0.891498 3.320936 12.574944\n11226 38.735928 0.922767 0.702902 2.647121 -0.833068 3.376809 12.172993\n11227 38.741401 0.740181 0.396089 2.646857 -0.617663 3.713996 11.454684\n11228 38.748102 0.636581 0.148857 2.653243 -0.525985 3.977547 10.623288\n11229 38.753463 0.618245 0.058111 2.654937 -0.539720 4.030319 10.288552\n11230 38.760043 0.623927 -0.063533 2.648697 -0.503372 3.921594 9.740743\n11231 38.765582 0.641628 -0.093117 2.641417 -0.448460 3.865685 9.503860\n11232 38.772010 0.714018 -0.090474 2.625277 -0.270213 3.886850 9.310815\n11233 38.777669 0.769672 -0.060843 2.615375 -0.188995 3.978734 9.240564\n11234 38.784034 0.910898 0.052550 2.584928 -0.249758 4.329841 8.935989\n11235 38.789627 0.985526 0.130861 2.563055 -0.346953 4.416043 8.848560\n11236 38.796079 1.111676 0.327047 2.504676 -0.646296 4.319219 8.911412\n11237 38.801780 1.157961 0.441665 2.469469 -0.830384 4.252440 9.011770\n11238 38.808058 1.213037 0.684244 2.400652 -1.109130 4.088666 9.246798\n11239 38.814021 1.224767 0.806303 2.375787 -1.196338 4.008589 9.383878\n11240 38.820123 1.239843 1.033658 2.362440 -1.234641 3.869033 9.718319\n11241 38.826027 1.242945 1.129866 2.373772 -1.167181 3.817614 9.864873\n11242 38.832141 1.238870 1.266596 2.419156 -0.805295 3.847560 10.168869\n11243 38.838183 1.228949 1.302602 2.449351 -0.497924 3.918999 10.353317\n11244 38.844030 1.186169 1.310183 2.522899 0.161820 4.223842 10.632036\n11245 38.850246 1.156073 1.283301 2.566347 0.419185 4.448167 10.652360\n11246 38.856117 1.097657 1.170719 2.664641 0.772043 4.858106 10.600924\n11247 38.862157 1.075027 1.090063 2.715995 0.899164 4.994945 10.571686\n11248 38.868200 1.048112 0.895562 2.811171 1.033838 5.113779 10.470037\n11249 38.874399 1.037891 0.787518 2.849489 1.051618 5.105355 10.383271\n11250 38.880385 0.999409 0.563420 2.896285 1.066595 5.076549 10.212022\n11251 38.886368 0.965552 0.452576 2.906230 1.105566 5.123264 10.103239\n11252 38.892399 0.870574 0.239081 2.911004 1.270327 5.189145 10.024940\n11253 38.898512 0.813984 0.135393 2.907984 1.330325 5.121853 10.066877\n11254 38.904606 0.705131 -0.065494 2.886097 1.314747 4.901258 10.265079\n11255 38.910583 0.655802 -0.160482 2.864787 1.291988 4.801536 10.380557\n11256 38.916636 0.560845 -0.332956 2.802356 1.377251 4.601322 10.506527\n11257 38.922774 0.511848 -0.407744 2.762350 1.457206 4.533157 10.476741\n11258 38.928675 0.408491 -0.536946 2.666670 1.642710 4.573748 10.342006\n11259 38.934687 0.356499 -0.594169 2.612276 1.749823 4.659988 10.267717\n11260 38.940735 0.271174 -0.698466 2.494153 1.959742 4.822834 10.155015\n11261 38.947016 0.241229 -0.748280 2.430130 2.053744 4.874743 10.143637\n11262 38.953009 0.198462 -0.846271 2.287770 2.218758 4.852038 10.066373\n11263 38.959021 0.179979 -0.893268 2.208460 2.313721 4.783957 9.997728\n11264 38.964814 0.132249 -0.977440 2.038416 2.553275 4.582490 9.837629\n11265 38.971126 0.091408 -1.021273 1.927976 2.699287 4.400940 9.701535\n11266 38.977049 0.013452 -1.078490 1.747264 2.867074 4.048590 9.561724\n11267 38.983053 -0.026358 -1.101859 1.655543 2.925853 3.877273 9.544691\n11268 38.989204 -0.101962 -1.139305 1.468213 3.028585 3.597760 9.535597\n11269 38.995350 -0.141938 -1.154902 1.374905 3.054135 3.485452 9.481736\n11270 39.001155 -0.241391 -1.183265 1.193648 3.094092 3.296252 9.224028\n11271 39.007112 -0.302246 -1.197500 1.107427 3.143589 3.198925 9.117911\n11272 39.013282 -0.441299 -1.231050 0.948616 3.416506 3.056911 9.031995\n11273 39.019198 -0.512013 -1.250953 0.877347 3.615901 3.066787 9.012123\n11274 39.025395 -0.637906 -1.296191 0.746658 3.959591 3.297519 8.949371\n11275 39.031359 -0.692779 -1.320092 0.684108 4.028477 3.422712 8.858411\n11276 39.037290 -0.793695 -1.363442 0.558806 3.945727 3.513998 8.611371\n11277 39.043312 -0.842198 -1.381047 0.494785 3.850041 3.553395 8.494570\n11278 39.049322 -0.936222 -1.406799 0.364811 3.679404 3.788836 8.340973\n11279 39.055449 -0.979130 -1.416515 0.300549 3.632015 3.940544 8.296770\n11280 39.061480 -1.051082 -1.435933 0.174182 3.581625 4.153289 8.232570\n11281 39.067727 -1.079441 -1.447348 0.112117 3.555450 4.174711 8.174079\n11282 39.073659 -1.121825 -1.475885 -0.011324 3.550462 4.190998 8.025723\n11283 39.079901 -1.140763 -1.492710 -0.072927 3.591712 4.234300 7.954323\n11284 39.085765 -1.185822 -1.528217 -0.192331 3.747162 4.308294 7.796820\n11285 39.091853 -1.213314 -1.546267 -0.249382 3.825646 4.274294 7.721988\n11286 39.097772 -1.274690 -1.584545 -0.361015 3.927456 4.046858 7.570131\n11287 39.103731 -1.305357 -1.605555 -0.417212 3.969705 3.926146 7.527877\n11288 39.109875 -1.365572 -1.653225 -0.528308 4.119489 3.745680 7.467557\n11289 39.116011 -1.395074 -1.678775 -0.581520 4.223461 3.701126 7.405410\n11290 39.121873 -1.457295 -1.725016 -0.681435 4.430476 3.574908 7.246425\n11291 39.128000 -1.492828 -1.741462 -0.728566 4.522722 3.448201 7.191477\n11292 39.134011 -1.570426 -1.752459 -0.816279 4.676019 3.139961 7.222303\n11293 39.140627 -1.648037 -1.728265 -0.887959 4.735775 2.952107 7.353663\n11294 39.146347 -1.687093 -1.703115 -0.914449 4.702720 2.920481 7.401830\n11295 39.152738 -1.761528 -1.638770 -0.947542 4.630289 3.100019 7.338549\n11296 39.158272 -1.792339 -1.603513 -0.955371 4.645934 3.380317 7.291873\n11297 39.164607 -1.845724 -1.531025 -0.958657 4.769877 3.870553 7.315280\n11298 39.170364 -1.869404 -1.496338 -0.957924 4.862860 3.919104 7.333197\n11299 39.176769 -1.907539 -1.435142 -0.960155 5.072403 3.789545 7.199760\n11300 39.182362 -1.921940 -1.409127 -0.961320 5.161739 3.718607 7.039658\n11301 39.188615 -1.943081 -1.362639 -0.954776 5.434238 3.691499 6.745366\n11302 39.194388 -1.949108 -1.338999 -0.945488 5.607334 3.766085 6.649731\n11303 39.200613 -1.954438 -1.284769 -0.918061 5.826611 3.972753 6.439607\n11304 39.206494 -1.956517 -1.253542 -0.905252 5.842889 4.055536 6.313308\n11305 39.212804 -1.964070 -1.183032 -0.889012 5.729242 4.214466 6.081316\n11306 39.218660 -1.971674 -1.144236 -0.883321 5.625569 4.275229 6.034513\n11307 39.224638 -1.995831 -1.063902 -0.871125 5.423957 4.272798 5.965564\n11308 39.230517 -2.009127 -1.024772 -0.862440 5.341790 4.225990 5.927156\n11309 39.236660 -2.033224 -0.953882 -0.836414 5.195947 3.987633 5.899544\n11310 39.242620 -2.043682 -0.922157 -0.821254 5.120610 3.787589 5.930337\n11311 39.248697 -2.061620 -0.867873 -0.796143 4.990037 3.408199 6.046542\n11312 39.254755 -2.070016 -0.845547 -0.788568 4.943479 3.263799 6.109814\n11313 39.260846 -2.090366 -0.809224 -0.783145 4.871093 3.144363 6.218855\n11314 39.267063 -2.104189 -0.793774 -0.782102 4.811458 3.202198 6.253559\n11315 39.272907 -2.139746 -0.764326 -0.776724 4.654622 3.570448 6.293217\n11316 39.279002 -2.156510 -0.749327 -0.771989 4.585804 3.789879 6.315709\n11317 39.284976 -2.181247 -0.719989 -0.765858 4.597251 4.111666 6.490772\n11318 39.290968 -2.191082 -0.705857 -0.766847 4.676805 4.187940 6.618179\n11319 39.297044 -2.210635 -0.676796 -0.776777 4.904943 4.163143 6.667709\n11320 39.303134 -2.221243 -0.662338 -0.783954 5.038485 4.067551 6.567838\n11321 39.309230 -2.245558 -0.637001 -0.794872 5.319504 3.835152 6.256017\n11322 39.315273 -2.255064 -0.625078 -0.795038 5.410928 3.753824 6.198952\n11323 39.321156 -2.259704 -0.599558 -0.785538 5.408510 3.693403 6.160306\n11324 39.327225 -2.251239 -0.585569 -0.779492 5.307162 3.708980 6.126651\n11325 39.333356 -2.227852 -0.559269 -0.771987 5.026865 3.735321 5.990840\n11326 39.339418 -2.217050 -0.547037 -0.772590 4.929263 3.770980 5.972695\n11327 39.345554 -2.194237 -0.518080 -0.777440 4.937958 3.997582 6.132137\n11328 39.351519 -2.180836 -0.499905 -0.777859 5.021919 4.131538 6.310836\n11329 39.357445 -2.149404 -0.457011 -0.770457 5.309958 4.135087 6.657939\n11330 39.363427 -2.131729 -0.434240 -0.764571 5.489570 3.971378 6.747364\n11331 39.369489 -2.093592 -0.394949 -0.753210 5.899757 3.472990 6.749363\n11332 39.375549 -2.074589 -0.380058 -0.748267 6.127542 3.230796 6.681177\n11333 39.381662 -2.035363 -0.356305 -0.738313 6.570169 2.924851 6.495067\n11334 39.387897 -2.014378 -0.344787 -0.731746 6.720092 2.891776 6.391917\n11335 39.393649 -1.969090 -0.313132 -0.717007 6.731801 3.057371 6.193005\n11336 39.399779 -1.945549 -0.289923 -0.710967 6.631152 3.249145 6.135136\n11337 39.405787 -1.902248 -0.227334 -0.707968 6.344476 3.646520 6.138656\n11338 39.411828 -1.886270 -0.188300 -0.712132 6.204254 3.802045 6.172972\n11339 39.417911 -1.873297 -0.101558 -0.731086 6.006413 4.031065 6.221300\n11340 39.423870 -1.876925 -0.056732 -0.742666 5.956405 4.052763 6.226536\n11341 39.429913 -1.904416 0.031311 -0.760424 6.037409 3.782018 6.302690\n11342 39.435900 -1.925957 0.072213 -0.763207 6.114305 3.514131 6.348932\n11343 39.442046 -1.980188 0.145018 -0.750539 6.153095 2.907682 6.494838\n11344 39.447956 -2.015126 0.175301 -0.735134 6.121886 2.663716 6.597909\n11345 39.453998 -2.089353 0.221361 -0.691837 5.976663 2.403107 6.722213\n11346 39.460060 -2.124383 0.236273 -0.664190 5.930736 2.289528 6.802292\n11347 39.466087 -2.188047 0.241749 -0.602838 6.028183 1.958683 7.039184\n11348 39.472200 -2.212305 0.231274 -0.572150 6.180437 1.826107 7.182583\n11349 39.478364 -2.229911 0.186135 -0.513808 6.517291 1.779851 7.427478\n11350 39.484195 -2.223455 0.153845 -0.489364 6.635888 1.791059 7.519212\n11351 39.490193 -2.193423 0.077471 -0.461134 6.708159 1.913344 7.745234\n11352 39.496330 -2.175363 0.035981 -0.460914 6.686443 2.063615 7.860053\n11353 39.502329 -2.142906 -0.048682 -0.490504 6.695300 2.285100 7.950332\n11354 39.508845 -2.130841 -0.091873 -0.518012 6.757911 2.230170 7.911304\n11355 39.514433 -2.120865 -0.192800 -0.591608 6.943116 1.820489 7.721184\n11356 39.520975 -2.126182 -0.278125 -0.644202 7.074337 1.451300 7.454193\n11357 39.526638 -2.130029 -0.313480 -0.657785 7.117173 1.340691 7.310363\n11358 39.532988 -2.133336 -0.341761 -0.661731 7.132607 1.311785 7.179486\n11359 39.538648 -2.139363 -0.372699 -0.648059 7.038840 1.424309 7.031970\n11360 39.545033 -2.137132 -0.367341 -0.626114 6.819974 1.538320 7.007740\n11361 39.550632 -2.130804 -0.353442 -0.616988 6.763746 1.539868 7.044838\n11362 39.557185 -2.099171 -0.308917 -0.600759 6.754470 1.518334 7.115014\n11363 39.562857 -2.073996 -0.279544 -0.590394 6.744988 1.539649 7.143011\n11364 39.569173 -2.014153 -0.211130 -0.565861 6.693522 1.592613 7.204341\n11365 39.574855 -1.983624 -0.173465 -0.556707 6.672324 1.549084 7.239795\n11366 39.581108 -1.935869 -0.098207 -0.557570 6.702778 1.222036 7.398973\n11367 39.586746 -1.925491 -0.064205 -0.571864 6.747258 0.999001 7.502908\n11368 39.593267 -1.931116 -0.011375 -0.626633 6.744328 0.700297 7.587440\n11369 39.599072 -1.940226 0.005778 -0.659285 6.725482 0.619980 7.558221\n11370 39.605194 -1.958437 0.017538 -0.718584 6.771466 0.514263 7.417809\n11371 39.610997 -1.961291 0.012714 -0.742014 6.849535 0.496244 7.320896\n11372 39.617152 -1.939572 -0.017146 -0.778535 7.073895 0.467980 7.201507\n11373 39.623110 -1.917147 -0.040364 -0.794479 7.198240 0.430309 7.218187\n11374 39.629316 -1.857992 -0.092302 -0.821204 7.293751 0.396235 7.321841\n11375 39.635202 -1.824957 -0.116475 -0.828671 7.224323 0.414453 7.373610\n11376 39.641267 -1.765220 -0.153062 -0.825073 6.989343 0.394095 7.455233\n11377 39.647321 -1.740520 -0.163882 -0.813251 6.881212 0.315038 7.497380\n11378 39.653269 -1.701752 -0.173775 -0.773732 6.857473 -0.038442 7.570191\n11379 39.659301 -1.688925 -0.176715 -0.752946 6.935411 -0.248217 7.589467\n11380 39.665306 -1.672927 -0.185559 -0.724297 7.064812 -0.552198 7.542463\n11381 39.671338 -1.669590 -0.191295 -0.718296 7.092175 -0.673041 7.448442\n11382 39.677624 -1.669209 -0.204455 -0.719723 7.074581 -0.826254 7.160715\n11383 39.683461 -1.670690 -0.212896 -0.722481 7.035641 -0.793279 6.983905\n11384 39.689559 -1.667846 -0.232589 -0.720509 6.987225 -0.606995 6.745987\n11385 39.695505 -1.659119 -0.244509 -0.715432 6.988451 -0.551293 6.709914\n11386 39.701749 -1.628137 -0.270962 -0.700789 7.005309 -0.569264 6.710641\n11387 39.707757 -1.609011 -0.285539 -0.691823 7.019965 -0.598950 6.711463\n11388 39.713719 -1.569392 -0.311825 -0.669419 6.996283 -0.531873 6.663720\n11389 39.719862 -1.549468 -0.320670 -0.653402 6.943016 -0.416596 6.636405\n11390 39.725673 -1.506168 -0.323828 -0.609004 6.799547 -0.153816 6.574031\n11391 39.731830 -1.482779 -0.317224 -0.581870 6.728833 -0.104713 6.601388\n11392 39.737781 -1.441897 -0.293461 -0.528018 6.621458 -0.286142 6.631557\n11393 39.743925 -1.419474 -0.277836 -0.503705 6.579686 -0.455408 6.577927\n11394 39.749942 -1.389259 -0.245295 -0.461023 6.516252 -0.835561 6.523290\n11395 39.755952 -1.383169 -0.228730 -0.439287 6.508632 -0.967033 6.497788\n11396 39.761894 -1.378657 -0.195604 -0.387824 6.616237 -1.146439 6.511053\n11397 39.768009 -1.378323 -0.182430 -0.357617 6.737850 -1.261296 6.460833\n11398 39.774158 -1.380909 -0.169712 -0.293475 7.087871 -1.494595 6.181320\n11399 39.780226 -1.380159 -0.168236 -0.260739 7.288190 -1.539751 6.015992\n11400 39.786017 -1.369219 -0.167292 -0.197640 7.628127 -1.510243 5.831992\n11401 39.792217 -1.357761 -0.162742 -0.169527 7.725539 -1.509209 5.824058\n11402 39.798284 -1.323701 -0.136718 -0.119800 7.776105 -1.619609 5.904576\n11403 39.804360 -1.302953 -0.114856 -0.097222 7.756315 -1.731590 5.949781\n11404 39.810505 -1.260234 -0.056525 -0.055624 7.700750 -1.969641 6.004793\n11405 39.816478 -1.237893 -0.023701 -0.036210 7.669963 -2.073330 6.018169\n11406 39.822368 -1.186639 0.038326 -0.002016 7.601577 -2.239789 5.989565\n11407 39.828458 -1.156240 0.062815 0.012208 7.530417 -2.338907 5.945755\n11408 39.834492 -1.085200 0.091550 0.036043 7.335373 -2.561533 5.871068\n11409 39.840562 -1.046998 0.094968 0.047176 7.263802 -2.666918 5.885220\n11410 39.846483 -0.971640 0.084233 0.072467 7.233489 -2.794827 6.003477\n11411 39.852592 -0.936988 0.072900 0.088574 7.264715 -2.828259 6.069630\n11412 39.858670 -0.879283 0.041541 0.125713 7.351164 -2.902388 6.174440\n11413 39.864597 -0.857285 0.024210 0.144345 7.391233 -2.931102 6.196510\n11414 39.870823 -0.826769 -0.006661 0.177672 7.453400 -2.949302 6.196067\n11415 39.876830 -0.817231 -0.018292 0.192217 7.484775 -2.950175 6.177518\n11416 39.882771 -0.805866 -0.030229 0.218749 7.536861 -3.001986 6.088738\n11417 39.888762 -0.805313 -0.030042 0.230704 7.539873 -3.071700 6.031047\n11418 39.894836 -0.816548 -0.019467 0.250409 7.504042 -3.253296 5.954703\n11419 39.900927 -0.825811 -0.008855 0.257757 7.452705 -3.325281 5.968750\n11420 39.906971 -0.843619 0.031002 0.265434 7.259387 -3.447996 6.052636\n11421 39.912925 -0.847836 0.054587 0.263692 7.158887 -3.520066 6.058864\n11422 39.919170 -0.848583 0.105718 0.252626 6.986554 -3.653674 6.042924\n11423 39.925176 -0.845818 0.129948 0.245115 6.952246 -3.687913 6.068524\n11424 39.931415 -0.830988 0.166951 0.232257 6.950055 -3.732098 6.162951\n11425 39.937226 -0.818994 0.176696 0.228751 6.949850 -3.752486 6.210886\n11426 39.943280 -0.790250 0.171887 0.227823 6.943256 -3.774930 6.278741\n11427 39.949218 -0.774583 0.157754 0.228344 6.943600 -3.748506 6.322269\n11428 39.955357 -0.740488 0.110313 0.228901 6.994061 -3.660889 6.404376\n11429 39.961360 -0.721797 0.079796 0.227157 7.038518 -3.642499 6.421763\n11430 39.967419 -0.687349 0.010475 0.216696 7.079733 -3.653441 6.343740\n11431 39.973416 -0.672632 -0.025722 0.208272 7.062392 -3.656444 6.248890\n11432 39.979455 -0.647811 -0.089699 0.187142 7.010336 -3.605200 6.101786\n11433 39.986141 -0.624018 -0.129986 0.165168 6.938655 -3.517997 6.038199\n11434 39.991754 -0.613122 -0.138500 0.155625 6.890314 -3.496677 6.010663\n11435 39.998141 -0.601873 -0.135374 0.138047 6.745223 -3.524298 5.956018\n11436 40.003679 -0.603028 -0.125143 0.129874 6.649948 -3.538161 5.941607\n11437 40.010497 -0.616975 -0.089518 0.116454 6.507813 -3.490748 5.939836\n11438 40.015896 -0.626805 -0.066392 0.111664 6.458143 -3.453891 5.932625\n11439 40.022381 -0.648113 -0.016098 0.104678 6.316566 -3.418457 5.911093\n11440 40.027902 -0.659805 0.008301 0.100579 6.248634 -3.418236 5.952960\n11441 40.034400 -0.686806 0.049141 0.085182 6.272702 -3.389062 6.234559\n11442 40.040009 -0.702528 0.063814 0.073524 6.392969 -3.365258 6.471210\n11443 40.046342 -0.741599 0.079763 0.042072 6.788026 -3.414841 6.962801\n11444 40.052142 -0.765508 0.081071 0.021742 7.008352 -3.481038 7.147034\n11445 40.058399 -0.818779 0.072231 -0.022520 7.452941 -3.659355 7.349500\n11446 40.064008 -0.843756 0.062783 -0.044099 7.678567 -3.793951 7.380211\n11447 40.070528 -0.880999 0.037694 -0.084075 8.097460 -4.163486 7.348955\n11448 40.076137 -0.890750 0.024312 -0.102508 8.276177 -4.342793 7.297627\n11449 40.082508 -0.889721 0.003800 -0.135873 8.535060 -4.644215 7.107803\n11450 40.088172 -0.879362 0.001062 -0.150262 8.603129 -4.760081 6.983127\n11451 40.094507 -0.838967 0.019698 -0.170759 8.588332 -4.981962 6.706043\n11452 40.100381 -0.809532 0.043978 -0.176559 8.529667 -5.094904 6.546030\n11453 40.106512 -0.727903 0.124619 -0.180525 8.361609 -5.247950 6.227667\n11454 40.112468 -0.674855 0.178328 -0.180439 8.291776 -5.280953 6.084107\n11455 40.118403 -0.545327 0.307147 -0.183455 8.225941 -5.271295 5.844714\n11456 40.124352 -0.473195 0.378308 -0.189131 8.212631 -5.239856 5.740160\n11457 40.130437 -0.328850 0.525120 -0.211457 8.149842 -5.176641 5.592017\n11458 40.136559 -0.263010 0.598953 -0.228442 8.080172 -5.150095 5.554265\n11459 40.143145 -0.153401 0.739102 -0.273022 7.774018 -5.064992 5.584192\n11460 40.148596 -0.102323 0.804449 -0.300493 7.526814 -4.935320 5.629835\n11461 40.154667 -0.032200 0.924967 -0.366390 7.108362 -4.710413 6.063189\n11462 40.160555 -0.009594 0.979738 -0.404129 6.961201 -4.591055 6.288446\n11463 40.166825 0.020364 1.077458 -0.485456 6.626693 -4.303878 6.596435\n11464 40.172823 0.024926 1.117234 -0.527131 6.410133 -4.185402 6.656179\n11465 40.178817 0.005927 1.173934 -0.606823 5.959617 -4.027183 6.629709\n11466 40.184811 -0.008426 1.193106 -0.641442 5.820710 -3.948207 6.657115\n11467 40.190838 -0.027445 1.214003 -0.700077 5.802691 -3.816248 6.851408\n11468 40.196860 -0.028031 1.216431 -0.724519 5.859388 -3.829712 6.951481\n11469 40.203068 -0.015075 1.209824 -0.763347 5.962746 -4.045392 7.015118\n11470 40.208972 -0.005535 1.201907 -0.777364 5.993628 -4.184307 6.972668\n11471 40.215109 0.018387 1.182762 -0.791871 5.956868 -4.399165 6.853050\n11472 40.221106 0.035898 1.174298 -0.791139 5.943337 -4.481850 6.813797\n11473 40.227046 0.091517 1.164131 -0.776323 6.011555 -4.662722 6.821763\n11474 40.233260 0.133731 1.164013 -0.764516 6.077363 -4.791822 6.840566\n11475 40.239246 0.252936 1.182156 -0.734467 6.257696 -5.117021 6.837828\n11476 40.245350 0.326764 1.203023 -0.716708 6.330242 -5.247777 6.840230\n11477 40.251404 0.488838 1.273587 -0.674251 6.337081 -5.329839 6.838381\n11478 40.257255 0.602112 1.339424 -0.643045 6.253784 -5.244843 6.839686\n11479 40.263336 0.808107 1.477897 -0.594302 6.066946 -5.011115 6.911790\n11480 40.269381 0.923664 1.561162 -0.574431 5.985614 -4.953518 6.949892\n11481 40.275613 1.177518 1.740643 -0.549693 5.825404 -5.049267 6.953710\n11482 40.281418 1.309096 1.833676 -0.544413 5.701252 -5.135869 6.884373\n11483 40.287459 1.558576 2.017308 -0.539114 5.296184 -5.143491 6.639293\n11484 40.293592 1.669273 2.103909 -0.536324 5.047513 -5.051342 6.554418\n11485 40.299768 1.858777 2.255661 -0.530394 4.611097 -4.914309 6.644002\n11486 40.305543 1.934425 2.316244 -0.529372 4.434661 -4.930185 6.813538\n11487 40.311813 2.043576 2.401272 -0.535603 4.161051 -4.945387 7.337070\n11488 40.317644 2.079945 2.424964 -0.543156 4.056786 -4.832982 7.630285\n11489 40.323916 2.121006 2.437851 -0.557987 3.895212 -4.446672 8.342972\n11490 40.329759 2.125423 2.427809 -0.562244 3.831048 -4.291857 8.640691\n11491 40.335864 2.106695 2.374391 -0.566493 3.680947 -4.125306 9.044184\n11492 40.341849 2.086651 2.328579 -0.568722 3.613822 -4.065634 9.234967\n11493 40.347889 2.042240 2.199443 -0.576609 3.539428 -3.864131 9.676912\n11494 40.353999 2.020689 2.117356 -0.582288 3.502862 -3.729644 9.920064\n11495 40.360069 1.970673 1.920395 -0.592795 3.416515 -3.626667 10.236292\n11496 40.366134 1.939596 1.810521 -0.596955 3.395500 -3.697007 10.303573\n11497 40.372060 1.868123 1.589472 -0.598376 3.430104 -3.956101 10.451570\n11498 40.378271 1.834282 1.484391 -0.593918 3.492770 -4.054256 10.546282\n11499 40.384231 1.795406 1.300302 -0.577916 3.606253 -3.813309 10.656199\n11500 40.390233 1.795817 1.224861 -0.567965 3.551647 -3.608780 10.683513\n11501 40.396285 1.834155 1.110555 -0.549692 3.278446 -3.437757 10.528284\n11502 40.402355 1.870513 1.069669 -0.543864 3.170410 -3.427374 10.411759\n11503 40.408610 1.964572 1.014094 -0.533570 3.081937 -3.305076 10.197661\n11504 40.414917 2.067469 0.981951 -0.515678 3.192169 -3.168738 10.157284\n11505 40.420509 2.115233 0.969861 -0.504341 3.224389 -3.080440 10.158934\n11506 40.426812 2.199661 0.952191 -0.478393 3.171646 -2.888014 10.132987\n11507 40.432601 2.231579 0.946363 -0.468033 3.134498 -2.795310 10.106442\n11508 40.438907 2.266488 0.941289 -0.461130 3.031107 -2.505646 10.105545\n11509 40.444716 2.269945 0.942582 -0.464927 2.992844 -2.356874 10.107207\n11510 40.450833 2.254467 0.949288 -0.484660 3.051038 -2.113957 10.044199\n11511 40.456674 2.235665 0.950144 -0.497456 3.123230 -2.032933 10.005679\n11512 40.463142 2.189641 0.940947 -0.518081 3.306848 -2.081996 9.959362\n11513 40.468701 2.164902 0.929616 -0.523638 3.360387 -2.194237 9.990789\n11514 40.475115 2.104546 0.893282 -0.523423 3.246111 -2.319984 10.000808\n11515 40.480830 2.068471 0.869418 -0.516782 3.101097 -2.179946 9.989890\n11516 40.486965 1.990349 0.821435 -0.492500 2.734407 -1.561610 9.977628\n11517 40.492921 1.945743 0.799640 -0.476774 2.529927 -1.151349 9.943439\n11518 40.499193 1.854432 0.759171 -0.442270 2.148545 -0.458300 9.969739\n11519 40.504999 1.813387 0.742530 -0.426045 2.033239 -0.230655 10.046615\n11520 40.511049 1.758265 0.718839 -0.396948 1.963736 0.109589 10.275968\n11521 40.517093 1.739540 0.712623 -0.381484 2.004622 0.255624 10.349624\n11522 40.523127 1.721313 0.717259 -0.341706 2.145397 0.550082 10.440986\n11523 40.528912 1.719214 0.728092 -0.316687 2.190683 0.727065 10.479547\n11524 40.535255 1.724319 0.764194 -0.257848 2.249714 1.194021 10.443824\n11525 40.541339 1.734085 0.788330 -0.225483 2.277816 1.503463 10.387243\n11526 40.547279 1.782875 0.843312 -0.154492 2.322462 2.025127 10.220510\n11527 40.553404 1.821465 0.873740 -0.115477 2.289804 2.141160 10.117455\n11528 40.559384 1.912325 0.938432 -0.030146 2.062533 2.165955 9.946914\n11529 40.565543 1.958941 0.971790 0.017051 1.895418 2.186174 9.875840\n11530 40.571331 2.047387 1.039148 0.120843 1.584851 2.399038 9.784979\n11531 40.577408 2.087104 1.070330 0.174274 1.464797 2.620289 9.790184\n11532 40.583335 2.154161 1.118879 0.271481 1.269349 3.192030 9.878656\n11533 40.589401 2.183966 1.135337 0.310753 1.208005 3.433265 9.967198\n11534 40.595551 2.242866 1.159672 0.368201 1.169283 3.669790 10.181715\n11535 40.601516 2.266879 1.171136 0.389196 1.173432 3.753647 10.277746\n11536 40.607769 2.282366 1.193300 0.425010 1.308823 3.865628 10.457109\n11537 40.613594 2.272428 1.203400 0.442657 1.396227 3.866580 10.577127\n11538 40.619912 2.229385 1.217718 0.478243 1.551143 3.827852 10.852433\n11539 40.625852 2.199963 1.220796 0.494054 1.560253 3.853618 10.945874\n11540 40.631732 2.124144 1.216948 0.520925 1.403268 4.072165 10.895201\n11541 40.637715 2.075046 1.208861 0.531328 1.270540 4.155549 10.724173\n11542 40.643779 1.914111 1.164322 0.554067 1.030042 4.442735 10.206221\n11543 40.649916 1.837841 1.129407 0.566846 1.026921 4.639451 9.807096\n11544 40.655957 1.689389 1.028102 0.599542 1.045376 5.098047 9.312663\n11545 40.661997 1.616531 0.962322 0.617164 0.999822 5.267260 9.173692\n11546 40.667890 1.489695 0.821358 0.643659 0.795660 5.477245 9.007894\n11547 40.674355 1.433624 0.749581 0.649515 0.664398 5.490759 8.992769\n11548 40.679960 1.311026 0.609863 0.648346 0.503107 5.316448 8.999927\n11549 40.686285 1.237074 0.546974 0.644849 0.542313 5.202560 9.099139\n11550 40.692305 1.067771 0.437933 0.641804 0.765074 4.956187 9.317917\n11551 40.698269 0.982077 0.394265 0.643147 0.915562 4.738915 9.424418\n11552 40.704248 0.838701 0.337131 0.642069 1.246195 4.270321 9.704206\n11553 40.710240 0.786720 0.327159 0.636101 1.344956 4.105969 9.796358\n11554 40.716331 0.711374 0.350528 0.611286 1.427687 3.698828 9.656759\n11555 40.722415 0.680857 0.379045 0.593487 1.434032 3.455631 9.494188\n11556 40.728470 0.626913 0.451568 0.552373 1.385668 3.178272 9.301593\n11557 40.734464 0.610096 0.488570 0.530905 1.374755 3.164735 9.358420\n11558 40.740603 0.621454 0.540128 0.488642 1.440424 3.330760 9.513789\n11559 40.746579 0.652669 0.549930 0.467553 1.427763 3.523013 9.534237\n11560 40.752535 0.739840 0.536317 0.421056 1.138076 3.895621 9.489661\n11561 40.758551 0.788484 0.517510 0.393352 0.892915 4.058196 9.424937\n11562 40.764626 0.873429 0.472117 0.335096 0.398946 4.189424 9.201700\n11563 40.770672 0.904520 0.445760 0.309537 0.241548 4.163393 9.127649\n11564 40.776830 0.951505 0.382751 0.273540 0.181000 4.070200 9.127541\n11565 40.782873 0.977491 0.345436 0.265249 0.232843 4.062598 9.190642\n11566 40.788896 1.038244 0.257716 0.267746 0.336140 4.084576 9.290805\n11567 40.794967 1.065832 0.209621 0.275442 0.357109 4.120103 9.252245\n11568 40.800889 1.092753 0.110807 0.296797 0.381865 4.249856 9.000690\n11569 40.807767 1.087946 0.061124 0.309205 0.425656 4.349689 8.821182\n11570 40.813038 1.049744 -0.034047 0.338455 0.545642 4.615409 8.516342\n11571 40.819081 1.024058 -0.077780 0.355966 0.587490 4.720689 8.450846\n11572 40.825198 0.976928 -0.155446 0.393957 0.646855 4.871278 8.384710\n11573 40.831664 0.958185 -0.188118 0.410525 0.657477 4.908091 8.334858\n11574 40.837367 0.917894 -0.236214 0.430650 0.619738 4.713377 8.348825\n11575 40.843735 0.860463 -0.247931 0.430785 0.559200 4.549274 8.508316\n11576 40.849415 0.833737 -0.236748 0.426574 0.507116 4.611198 8.472315\n11577 40.855894 0.800432 -0.189272 0.418901 0.418077 4.886390 8.244206\n11578 40.861412 0.800085 -0.159077 0.417797 0.426357 5.011676 8.114274\n11579 40.867904 0.849572 -0.089728 0.421004 0.512149 5.170161 8.002395\n11580 40.873664 0.895502 -0.054807 0.424442 0.565336 5.177999 8.017420\n11581 40.879796 0.995893 0.008312 0.435178 0.670608 5.141571 8.021440\n11582 40.885570 1.038176 0.036274 0.444838 0.713914 5.165854 8.057806\n11583 40.891755 1.091367 0.084376 0.478173 0.810453 5.316194 8.138712\n11584 40.897796 1.104635 0.102522 0.501131 0.870870 5.431704 8.140469\n11585 40.903773 1.112063 0.121661 0.550505 0.990310 5.735423 8.166836\n11586 40.909664 1.110262 0.122489 0.573086 1.022482 5.838630 8.160428\n11587 40.915921 1.093328 0.113324 0.608638 0.994615 5.901602 8.093020\n11588 40.921747 1.080516 0.106624 0.620722 0.948108 5.914780 8.059027\n11589 40.927983 1.033310 0.100183 0.636844 0.899175 5.852552 7.885248\n11590 40.933919 1.001606 0.099528 0.643113 0.879801 5.801807 7.806527\n11591 40.940006 0.932972 0.096312 0.652795 0.758672 5.692927 7.798341\n11592 40.945892 0.905540 0.092789 0.653711 0.673916 5.652539 7.861605\n11593 40.951891 0.863356 0.074488 0.637464 0.555381 5.635816 7.969246\n11594 40.958131 0.844944 0.057427 0.619345 0.611252 5.690476 7.893462\n11595 40.964143 0.812944 0.011230 0.565689 0.918620 5.949195 7.555111\n11596 40.970286 0.795433 -0.019134 0.533628 1.092333 6.095987 7.411922\n11597 40.976131 0.757171 -0.093443 0.464547 1.370024 6.280311 7.247388\n11598 40.982139 0.740593 -0.135223 0.427803 1.471399 6.289261 7.261308\n11599 40.988265 0.712003 -0.223216 0.350827 1.610327 6.143181 7.407218\n11600 40.994218 0.697617 -0.267276 0.310392 1.654583 6.043571 7.430898\n11601 41.000376 0.665077 -0.351330 0.227182 1.707588 5.952641 7.312859\n11602 41.006390 0.643514 -0.391925 0.186610 1.708400 5.968453 7.275767\n11603 41.012410 0.595168 -0.469025 0.112385 1.697428 6.056712 7.298690\n11604 41.018378 0.574658 -0.504326 0.078374 1.736658 6.127282 7.320455\n11605 41.024518 0.554899 -0.573326 0.014373 1.884527 6.333646 7.302226\n11606 41.030462 0.550622 -0.605971 -0.015869 1.993425 6.355667 7.246309\n11607 41.036478 0.547648 -0.667785 -0.075320 2.154659 6.278295 7.240804\n11608 41.042522 0.546639 -0.695077 -0.103509 2.158898 6.247542 7.264379\n11609 41.048633 0.535623 -0.735457 -0.154291 2.183254 6.124433 7.320627\n11610 41.054666 0.523170 -0.750408 -0.176221 2.240157 6.022195 7.362596\n11611 41.060639 0.476278 -0.770417 -0.213466 2.482349 5.793421 7.430934\n11612 41.066778 0.445822 -0.778269 -0.230494 2.630939 5.714489 7.525012\n11613 41.072867 0.376483 -0.795639 -0.265256 2.905891 5.586714 7.750042\n11614 41.078809 0.339513 -0.804907 -0.283606 3.038955 5.533862 7.865688\n11615 41.084845 0.269195 -0.823396 -0.319598 3.283043 5.486044 7.925864\n11616 41.090822 0.240340 -0.830906 -0.334840 3.335124 5.511760 7.807083\n11617 41.096752 0.200132 -0.839217 -0.358397 3.171084 5.613671 7.535857\n11618 41.102851 0.188537 -0.839330 -0.369109 2.973068 5.631047 7.410321\n11619 41.108973 0.180356 -0.831961 -0.398992 2.525723 5.591010 7.186350\n11620 41.114944 0.178546 -0.827610 -0.420343 2.331701 5.601724 7.090064\n11621 41.120889 0.163826 -0.824182 -0.478567 2.066272 5.828622 6.889898\n11622 41.126947 0.145089 -0.827208 -0.513554 1.986056 5.990041 6.818788\n11623 41.133082 0.077255 -0.850588 -0.590614 1.916915 6.248520 6.718043\n11624 41.139310 0.033481 -0.871174 -0.632025 1.943428 6.338706 6.654396\n11625 41.145254 -0.058896 -0.927075 -0.719667 2.115988 6.539790 6.557199\n11626 41.151197 -0.105214 -0.960936 -0.763834 2.208148 6.619627 6.539253\n11627 41.157404 -0.189925 -1.029651 -0.848722 2.350497 6.605925 6.494506\n11628 41.163280 -0.223358 -1.061717 -0.887892 2.403754 6.547768 6.462979\n11629 41.169372 -0.268966 -1.119327 -0.957161 2.485480 6.408073 6.459214\n11630 41.175321 -0.280944 -1.144163 -0.987826 2.535010 6.343094 6.497925\n11631 41.181468 -0.284378 -1.185655 -1.045292 2.560076 6.290660 6.570798\n11632 41.187592 -0.278136 -1.204198 -1.075532 2.495434 6.317703 6.521764\n11633 41.193484 -0.257538 -1.240262 -1.150153 2.194808 6.483498 6.270821\n11634 41.199681 -0.250163 -1.258332 -1.196084 1.989884 6.597732 6.146915\n11635 41.205693 -0.248599 -1.294113 -1.301092 1.649779 6.923035 6.021118\n11636 41.211807 -0.252276 -1.310468 -1.356262 1.565095 7.115106 6.018659\n11637 41.217685 -0.272177 -1.339005 -1.464357 1.571384 7.244048 6.145646\n11638 41.223682 -0.294407 -1.351831 -1.514201 1.701209 7.082790 6.265294\n11639 41.229829 -0.370286 -1.373091 -1.601761 2.124582 6.594833 6.497540\n11640 41.235820 -0.420967 -1.381854 -1.637790 2.343299 6.404712 6.560379\n11641 41.241903 -0.550546 -1.405258 -1.690711 2.717729 6.196057 6.568846\n11642 41.247839 -0.618902 -1.421075 -1.708917 2.804867 6.280439 6.594399\n11643 41.254073 -0.741583 -1.447926 -1.734546 2.735488 6.755351 6.577690\n11644 41.260709 -0.788941 -1.457370 -1.745064 2.608269 7.058775 6.449118\n11645 41.266060 -0.855730 -1.467611 -1.768110 2.157330 7.724051 5.972332\n11646 41.272581 -0.881646 -1.461343 -1.796618 1.572260 8.209898 5.668914\n11647 41.278097 -0.880221 -1.451624 -1.811607 1.320068 8.298265 5.652908\n11648 41.284653 -0.851628 -1.419442 -1.833882 1.054394 8.248457 5.769332\n11649 41.290303 -0.828390 -1.398781 -1.837506 1.072746 8.155313 5.871220\n11650 41.296990 -0.790023 -1.356111 -1.824741 1.289786 7.726362 6.091244\n11651 41.302350 -0.786689 -1.335827 -1.809306 1.400194 7.421908 6.202323\n11652 41.308872 -0.826200 -1.298988 -1.769666 1.560486 6.932343 6.400665\n11653 41.314303 -0.870735 -1.282842 -1.747438 1.639128 6.824977 6.506130\n11654 41.320925 -1.005513 -1.252500 -1.697877 1.820810 6.846320 6.686219\n11655 41.326327 -1.089132 -1.236562 -1.670076 1.886134 6.955320 6.725523\n11656 41.332887 -1.264241 -1.200616 -1.610981 1.846301 7.322749 6.619636\n11657 41.338635 -1.347978 -1.180633 -1.581105 1.776355 7.520477 6.447033\n11658 41.344885 -1.493433 -1.139246 -1.523486 1.635039 8.013903 6.004343\n11659 41.350645 -1.549967 -1.118694 -1.495488 1.562474 8.330587 5.846028\n11660 41.356857 -1.625509 -1.076699 -1.439003 1.536776 8.850942 5.725640\n11661 41.362626 -1.645095 -1.056767 -1.409391 1.616530 8.981936 5.764317\n11662 41.368759 -1.656057 -1.024092 -1.342195 1.920533 8.935787 6.020833\n11663 41.374731 -1.650787 -1.009761 -1.302687 2.107273 8.772430 6.229647\n11664 41.381221 -1.629729 -0.982937 -1.213137 2.410418 8.289819 6.731226\n11665 41.386866 -1.618158 -0.969666 -1.164086 2.475627 8.030628 6.949079\n11666 41.392756 -1.590647 -0.941372 -1.063503 2.461732 7.659344 7.174002\n11667 41.398911 -1.570052 -0.925825 -1.013842 2.404923 7.599495 7.195770\n11668 41.404998 -1.505388 -0.891163 -0.913813 2.294197 7.589775 7.134184\n11669 41.411095 -1.458465 -0.869781 -0.863301 2.252500 7.549312 7.047100\n11670 41.417055 -1.340111 -0.817805 -0.760473 2.112870 7.445058 6.836044\n11671 41.423047 -1.272121 -0.788007 -0.707107 2.032078 7.424084 6.715578\n11672 41.429207 -1.132981 -0.724519 -0.596712 1.947164 7.358053 6.624217\n11673 41.435117 -1.068396 -0.692375 -0.539903 1.897262 7.288056 6.702584\n11674 41.441351 -0.963069 -0.627720 -0.426348 1.732885 7.075061 6.926267\n11675 41.447176 -0.926866 -0.597278 -0.370988 1.665649 6.951680 7.019014\n11676 41.453280 -0.901021 -0.546755 -0.261786 1.626412 6.827642 7.146926\n11677 41.459352 -0.913459 -0.528600 -0.207646 1.671710 6.872410 7.175040\n11678 41.465430 -0.982634 -0.512479 -0.104989 1.922498 7.100661 7.207902\n11679 41.471594 -1.035006 -0.515505 -0.058173 2.098317 7.261656 7.214847\n11680 41.477479 -1.164698 -0.540122 0.022763 2.444078 7.564999 7.231754\n11681 41.483468 -1.237972 -0.558275 0.056408 2.584521 7.661164 7.217003\n11682 41.489438 -1.406028 -0.598599 0.118947 2.785821 7.719953 7.082253\n11683 41.495533 -1.475530 -0.613877 0.142444 2.799538 7.706043 7.031583\n11684 41.501556 -1.597371 -0.635790 0.184205 2.635683 7.591480 6.963044\n11685 41.507795 -1.649434 -0.642421 0.202785 2.528152 7.469413 6.965330\n11686 41.513666 -1.738555 -0.654053 0.236509 2.522554 7.112842 7.052181\n11687 41.519639 -1.775417 -0.660093 0.252497 2.623407 6.960860 7.168287\n11688 41.525758 -1.830414 -0.669402 0.287913 2.910285 6.730173 7.565688\n11689 41.531794 -1.849894 -0.669122 0.309187 3.021664 6.622620 7.726552\n11690 41.537793 -1.875746 -0.650627 0.361046 3.070167 6.506353 7.784878\n11691 41.543810 -1.882756 -0.632320 0.390225 3.027782 6.481590 7.720359\n11692 41.549940 -1.881565 -0.577039 0.447322 2.934116 6.379953 7.626283\n11693 41.555918 -1.871511 -0.541526 0.473187 2.894752 6.301636 7.649714\n11694 41.562067 -1.839020 -0.458575 0.517992 2.766395 6.067675 7.704455\n11695 41.567924 -1.821334 -0.411492 0.537627 2.674591 5.915658 7.701643\n11696 41.574050 -1.799544 -0.307855 0.575404 2.493721 5.572636 7.659253\n11697 41.580100 -1.800634 -0.251928 0.594881 2.420652 5.415215 7.640771\n11698 41.586009 -1.824210 -0.135869 0.633794 2.320737 5.132109 7.753358\n11699 41.592290 -1.842665 -0.078383 0.650411 2.274895 5.018281 7.860870\n11700 41.598226 -1.882643 0.027447 0.676744 2.193576 4.915339 7.997406\n11701 41.604351 -1.902894 0.071820 0.688905 2.207235 4.908368 8.017916\n11702 41.610281 -1.943208 0.138608 0.718206 2.366216 4.878132 8.032237\n11703 41.616304 -1.961460 0.160120 0.737952 2.538035 4.825706 8.076524\n11704 41.622432 -1.992477 0.177556 0.790003 3.028986 4.721136 8.287725\n11705 41.628401 -2.005019 0.174546 0.822910 3.239962 4.701828 8.413061\n11706 41.634419 -2.024038 0.149085 0.901512 3.373727 4.670227 8.648177\n11707 41.640436 -2.030890 0.129235 0.946138 3.321336 4.618537 8.716435\n11708 41.646579 -2.040428 0.082107 1.045968 3.230477 4.371770 8.821918\n11709 41.652636 -2.044512 0.056397 1.101508 3.225949 4.223629 8.887813\n11710 41.658741 -2.053090 0.007919 1.221798 3.203825 3.926728 9.077588\n11711 41.664666 -2.058438 -0.012480 1.284396 3.145768 3.723679 9.136707\n11712 41.670746 -2.078434 -0.048561 1.408546 2.899849 3.130615 9.182780\n11713 41.677358 -2.093974 -0.067154 1.465371 2.769201 2.791052 9.226057\n11714 41.683045 -2.125031 -0.108160 1.565948 2.645407 2.214385 9.342502\n11715 41.688857 -2.137490 -0.132225 1.614289 2.659082 2.023464 9.406130\n11716 41.693844 -2.157522 -0.190848 1.712493 2.705101 1.888897 9.424538\n11717 41.699892 -2.164212 -0.223668 1.761625 2.692907 1.922044 9.382456\n11718 41.706111 -2.168928 -0.295139 1.856604 2.710692 1.991909 9.298564\n11719 41.711989 -2.165504 -0.333772 1.901768 2.770609 1.986173 9.295560\n11720 41.718109 -2.141880 -0.411814 1.986529 2.916120 2.026443 9.337755\n11721 41.724156 -2.118526 -0.449767 2.027272 2.963605 2.111767 9.353209\n11722 41.730275 -2.050931 -0.519797 2.111528 3.006996 2.238991 9.350449\n11723 41.736172 -2.009916 -0.549130 2.154978 3.030372 2.235592 9.346650\n11724 41.742211 -1.919058 -0.593190 2.238233 3.050976 2.132677 9.255149\n11725 41.748355 -1.872372 -0.606526 2.274367 3.038214 2.025261 9.182260\n11726 41.754334 -1.782509 -0.613465 2.329943 3.032964 1.708979 8.965409\n11727 41.760239 -1.740672 -0.606334 2.350097 3.098933 1.538746 8.826229\n11728 41.766422 -1.659562 -0.566501 2.382354 3.486791 1.230395 8.492140\n11729 41.772496 -1.621570 -0.532164 2.397560 3.704581 1.012080 8.328909\n11730 41.778977 -1.562092 -0.434785 2.427617 3.915252 0.311291 8.127516\n11731 41.784657 -1.546628 -0.373669 2.439537 3.902434 -0.145734 8.102176\n11732 41.790516 -1.546051 -0.234787 2.452980 3.691487 -0.993264 8.080085\n11733 41.796546 -1.562946 -0.163469 2.456518 3.571506 -1.299101 8.150414\n11734 41.802640 -1.619046 -0.032083 2.463274 3.435292 -1.627994 8.445867\n11735 41.808606 -1.650150 0.023516 2.467888 3.403492 -1.736192 8.628116\n11736 41.814859 -1.711829 0.102587 2.475070 3.319682 -2.047989 8.920690\n11737 41.820628 -1.744060 0.123872 2.471929 3.278800 -2.190977 8.994881\n11738 41.826824 -1.805086 0.135989 2.444105 3.188403 -2.253517 9.193187\n11739 41.832906 -1.830649 0.130083 2.419235 3.139631 -2.210669 9.320005\n11740 41.839042 -1.864809 0.098607 2.347348 3.029726 -2.179020 9.518018\n11741 41.844905 -1.871148 0.073114 2.300672 2.983850 -2.215457 9.597083\n11742 41.851056 -1.859719 -0.001753 2.189804 2.918356 -2.407266 9.680473\n11743 41.857040 -1.840468 -0.051028 2.126537 2.867318 -2.549345 9.724134\n11744 41.863157 -1.776379 -0.171940 1.986997 2.666182 -2.877192 9.859002\n11745 41.869033 -1.734404 -0.242475 1.913417 2.557227 -3.005778 9.918323\n11746 41.875165 -1.622621 -0.413353 1.749062 2.619040 -3.059012 9.820418\n11747 41.882131 -1.502251 -0.562999 1.615850 3.028173 -3.044680 9.496302\n11748 41.888120 -1.435897 -0.631183 1.556998 3.260782 -3.149534 9.292281\n11749 41.894272 -1.304104 -0.744285 1.446548 3.591809 -3.622918 8.905800\n11750 41.900263 -1.244352 -0.785277 1.393281 3.676545 -3.875413 8.756335\n11751 41.906338 -1.146229 -0.828091 1.297515 3.723344 -4.178156 8.555727\n11752 41.912297 -1.109856 -0.827624 1.257945 3.685303 -4.247915 8.485007\n11753 41.918278 -1.064876 -0.785955 1.197006 3.509533 -4.445565 8.370652\n11754 41.924582 -1.053098 -0.747137 1.172372 3.418772 -4.593397 8.319986\n11755 41.930478 -1.036173 -0.643310 1.123400 3.288308 -4.877512 8.192309\n11756 41.936577 -1.026197 -0.582952 1.096372 3.242295 -5.028092 8.124839\n11757 41.942601 -0.995455 -0.455659 1.035434 3.280369 -5.291440 7.977283\n11758 41.948586 -0.973491 -0.392668 1.002107 3.348341 -5.349219 7.915142\n11759 41.954694 -0.915592 -0.274684 0.933275 3.512801 -5.354211 7.864115\n11760 41.960535 -0.879824 -0.221847 0.896851 3.590016 -5.347724 7.902573\n11761 41.966659 -0.797307 -0.131263 0.812105 3.616454 -5.404207 8.037034\n11762 41.972676 -0.752709 -0.094446 0.762416 3.563160 -5.497924 8.102588\n11763 41.978733 -0.662766 -0.037904 0.646908 3.434396 -5.687632 8.220410\n11764 41.984863 -0.617961 -0.015987 0.585823 3.409675 -5.744248 8.264614\n11765 41.990881 -0.527349 0.019927 0.471860 3.430348 -5.819643 8.372953\n11766 41.996845 -0.480756 0.034393 0.420579 3.437680 -5.867050 8.439504\n11767 42.003129 -0.380600 0.055774 0.321629 3.416785 -6.038084 8.578507\n11768 42.008878 -0.325785 0.061867 0.269804 3.420134 -6.150105 8.632419\n11769 42.015095 -0.206472 0.061998 0.153754 3.499941 -6.314024 8.676274\n11770 42.021130 -0.143129 0.055731 0.089298 3.552898 -6.309827 8.690831\n11771 42.027094 -0.008139 0.034614 -0.046353 3.641999 -6.118371 8.708216\n11772 42.033212 0.063731 0.022708 -0.115249 3.682222 -6.006740 8.714630\n11773 42.039217 0.212649 -0.000578 -0.255197 3.682803 -5.966506 8.667931\n11774 42.045343 0.287220 -0.010518 -0.328664 3.651221 -6.046801 8.624487\n11775 42.051211 0.432574 -0.022603 -0.488749 3.549892 -6.266723 8.525102\n11776 42.057284 0.500764 -0.022162 -0.574135 3.505226 -6.332489 8.489472\n11777 42.063265 0.625122 -0.004163 -0.744902 3.391117 -6.336452 8.470186\n11778 42.069473 0.681844 0.015466 -0.826088 3.308111 -6.303599 8.469944\n11779 42.075563 0.791051 0.076832 -0.977964 3.176404 -6.174860 8.417755\n11780 42.081486 0.845197 0.116777 -1.049457 3.152354 -6.080035 8.392684\n11781 42.087611 0.957574 0.208885 -1.184761 3.196259 -5.863021 8.359557\n11782 42.093538 1.018446 0.259910 -1.248250 3.241107 -5.731112 8.321623\n11783 42.099562 1.151780 0.367079 -1.359831 3.340215 -5.378934 8.241702\n11784 42.106167 1.223836 0.421497 -1.404751 3.411931 -5.142766 8.238102\n11785 42.111710 1.379641 0.528859 -1.466521 3.570517 -4.608862 8.328496\n11786 42.118243 1.463692 0.579114 -1.482839 3.609105 -4.360573 8.415979\n11787 42.123756 1.631071 0.665941 -1.494639 3.586163 -3.978085 8.614347\n11788 42.130474 1.793997 0.727436 -1.492027 3.544896 -3.741777 8.772708\n11789 42.135988 1.872051 0.748147 -1.485764 3.560090 -3.617477 8.855057\n11790 42.142203 2.010560 0.766887 -1.459627 3.664612 -3.308296 8.976464\n11791 42.147827 2.067664 0.765335 -1.439966 3.714601 -3.139060 9.018866\n11792 42.154183 2.156639 0.743630 -1.393510 3.704101 -2.913871 9.081401\n11793 42.159845 2.188221 0.727369 -1.371698 3.658048 -2.883272 9.137118\n11794 42.166315 2.226143 0.689267 -1.343462 3.557093 -2.831404 9.264227\n11795 42.171971 2.232179 0.669207 -1.337906 3.503405 -2.799158 9.322690\n11796 42.178457 2.228184 0.631177 -1.342197 3.426320 -2.656227 9.476032\n11797 42.184281 2.223269 0.613984 -1.349391 3.408638 -2.535951 9.530292\n11798 42.190473 2.208478 0.581586 -1.367635 3.475497 -2.280041 9.547573\n11799 42.196351 2.199214 0.563774 -1.379094 3.567866 -2.121909 9.513359\n11800 42.202485 2.180909 0.522921 -1.407285 3.654953 -1.697785 9.440938\n11801 42.208303 2.172042 0.502372 -1.422420 3.594990 -1.462657 9.441046\n11802 42.214473 2.149287 0.468234 -1.449750 3.332844 -1.026073 9.459757\n11803 42.220328 2.133884 0.457432 -1.459286 3.185286 -0.867272 9.469452\n11804 42.226603 2.093535 0.451650 -1.465235 3.069449 -0.687021 9.373634\n11805 42.232482 2.067433 0.454806 -1.461325 3.123796 -0.643336 9.323063\n11806 42.238603 2.012139 0.468080 -1.443291 3.339744 -0.546528 9.357387\n11807 42.244386 1.989071 0.478755 -1.431964 3.471994 -0.449636 9.448502\n11808 42.250596 1.956553 0.505189 -1.411644 3.708279 -0.266114 9.577833\n11809 42.256600 1.949360 0.520139 -1.403397 3.772534 -0.201303 9.597566\n11810 42.262748 1.956871 0.556020 -1.388359 3.834005 -0.020768 9.586358\n11811 42.269771 1.969795 0.576432 -1.380090 3.856266 0.209252 9.537050\n11812 42.274753 2.018161 0.621381 -1.352732 3.817724 0.894128 9.424855\n11813 42.280759 2.047421 0.640787 -1.338431 3.787825 1.117383 9.404036\n11814 42.286937 2.111016 0.674251 -1.314491 3.622234 1.353081 9.435730\n11815 42.292869 2.141031 0.687748 -1.305721 3.468557 1.424520 9.451385\n11816 42.299020 2.188894 0.711415 -1.295256 3.132548 1.512877 9.532909\n11817 42.304904 2.204104 0.723439 -1.292819 2.965555 1.519245 9.559895\n11818 42.311040 2.212562 0.750357 -1.287993 2.697553 1.486812 9.506355\n11819 42.317120 2.207332 0.764062 -1.286908 2.616193 1.472700 9.468088\n11820 42.323030 2.182466 0.787306 -1.291672 2.519773 1.482304 9.479574\n11821 42.329159 2.166382 0.796084 -1.297306 2.483384 1.499356 9.541387\n11822 42.335287 2.123616 0.808795 -1.311098 2.449000 1.479233 9.633347\n11823 42.341279 2.092483 0.811426 -1.317578 2.435416 1.469964 9.587578\n11824 42.347363 2.006665 0.808637 -1.320066 2.370983 1.565652 9.449754\n11825 42.353228 1.955224 0.802243 -1.313909 2.326210 1.684948 9.478110\n11826 42.359261 1.853477 0.784054 -1.290925 2.191036 1.964145 9.670282\n11827 42.365302 1.808970 0.772878 -1.278083 2.119170 2.087320 9.763195\n11828 42.371399 1.731675 0.746098 -1.260631 2.115193 2.293048 9.783040\n11829 42.377519 1.701494 0.731196 -1.256520 2.201379 2.405432 9.712888\n11830 42.383482 1.654917 0.703489 -1.246467 2.559465 2.619032 9.634043\n11831 42.389424 1.638788 0.692217 -1.238601 2.790689 2.720575 9.595555\n11832 42.395503 1.626430 0.677213 -1.216637 3.100439 2.909019 9.413491\n11833 42.401688 1.634789 0.673706 -1.203044 3.129491 2.986627 9.262382\n11834 42.407675 1.665635 0.676776 -1.178501 2.873873 3.081687 9.185694\n11835 42.413559 1.686151 0.683052 -1.170556 2.609961 3.133312 9.160571\n11836 42.419676 1.711628 0.708244 -1.162020 2.018134 3.262875 9.119045\n11837 42.425716 1.714953 0.723640 -1.159109 1.759303 3.328212 9.098195\n11838 42.431683 1.718946 0.759141 -1.148690 1.357072 3.528596 9.060720\n11839 42.437759 1.732140 0.779528 -1.140610 1.239024 3.672254 9.074430\n11840 42.443786 1.772174 0.821195 -1.125847 1.149269 3.895275 9.068023\n11841 42.449814 1.794041 0.841311 -1.121042 1.149299 3.975275 9.063329\n11842 42.455919 1.848659 0.881285 -1.114500 1.187284 4.201275 8.924520\n11843 42.461923 1.883240 0.904148 -1.111597 1.184193 4.378759 8.859144\n11844 42.468027 1.947460 0.955618 -1.098527 1.150451 4.805834 8.779513\n11845 42.474116 1.981184 0.984364 -1.087338 1.134786 4.992081 8.671057\n11846 42.480043 2.057328 1.047530 -1.058965 1.085446 5.278207 8.554047\n11847 42.486028 2.095045 1.078349 -1.044354 1.034365 5.364535 8.482617\n11848 42.492243 2.165928 1.144275 -1.020012 0.877230 5.444201 8.276933\n11849 42.498289 2.194441 1.179698 -1.010515 0.820530 5.438372 8.192615\n11850 42.504338 2.229490 1.256783 -0.992765 0.751245 5.449287 8.023262\n11851 42.510370 2.237857 1.300103 -0.983325 0.735949 5.486561 7.995091\n11852 42.516375 2.238206 1.396173 -0.966290 0.745915 5.463172 8.067225\n11853 42.522463 2.227287 1.447948 -0.961376 0.740735 5.403605 8.086889\n11854 42.528422 2.183433 1.555494 -0.962256 0.661546 5.250658 8.047287\n11855 42.535184 2.117583 1.658196 -0.978589 0.545869 5.140938 8.045572\n11856 42.540527 2.080262 1.711199 -0.989055 0.496198 5.142157 8.082526\n11857 42.547135 2.039799 1.765904 -0.998769 0.439912 5.188316 8.084823\n11858 42.552679 1.952270 1.873440 -1.011496 0.204411 5.419564 7.924127\n11859 42.559381 1.863852 1.968336 -1.009780 -0.135984 5.726313 7.714167\n11860 42.564706 1.822212 2.008128 -1.005453 -0.353711 5.840834 7.642488\n11861 42.571164 1.745336 2.069508 -0.992624 -0.707436 6.015655 7.701736\n11862 42.576653 1.708488 2.090140 -0.982471 -0.801418 6.082881 7.741441\n11863 42.583253 1.632530 2.116118 -0.945410 -0.952762 6.262711 7.852275\n11864 42.588871 1.591515 2.121346 -0.915974 -1.076085 6.367797 7.896011\n11865 42.595206 1.509008 2.121789 -0.837207 -1.386227 6.419880 7.885528\n11866 42.600988 1.465727 2.116341 -0.790287 -1.515255 6.351786 7.928039\n11867 42.607499 1.389163 2.094912 -0.688599 -1.685286 6.164319 7.965305\n11868 42.612951 1.352431 2.081199 -0.635073 -1.741498 6.193822 8.070089\n11869 42.619332 1.283704 2.048310 -0.516921 -1.673901 6.434390 8.095699\n11870 42.624991 1.252191 2.031724 -0.450073 -1.614088 6.603845 8.000178\n11871 42.631350 1.189444 1.993862 -0.299634 -1.680582 6.966020 7.764134\n11872 42.637141 1.149873 1.966247 -0.199808 -1.830361 7.147326 7.587358\n11873 42.643355 1.104591 1.919099 -0.038866 -2.174577 7.379313 7.323737\n11874 42.649312 1.088146 1.892424 0.040253 -2.350170 7.484705 7.191240\n11875 42.655513 1.063728 1.834633 0.192185 -2.778474 7.706728 6.787511\n11876 42.661415 1.054258 1.805587 0.265309 -2.955642 7.790777 6.607769\n11877 42.667689 1.020940 1.742517 0.407380 -3.006391 7.881103 6.508187\n11878 42.673237 0.993623 1.712018 0.475688 -2.906013 7.867486 6.584620\n11879 42.679631 0.930326 1.648076 0.602898 -2.528209 7.690914 6.910047\n11880 42.685407 0.884583 1.611575 0.661002 -2.356554 7.594051 7.147986\n11881 42.691574 0.768154 1.533083 0.771356 -2.219313 7.606121 7.285910\n11882 42.697504 0.703863 1.494157 0.826525 -2.239810 7.741814 7.242934\n11883 42.703689 0.555592 1.410189 0.942834 -2.383391 8.038793 6.947777\n11884 42.709651 0.476493 1.367210 1.002384 -2.486973 8.123528 6.693987\n11885 42.715742 0.328087 1.281337 1.116500 -2.643775 8.193125 6.325553\n11886 42.721596 0.258480 1.236380 1.169772 -2.603381 8.191727 6.217551\n11887 42.727819 0.123700 1.147597 1.269476 -2.413912 8.230467 6.080403\n11888 42.733823 0.056759 1.106876 1.316205 -2.355460 8.271774 6.031284\n11889 42.739863 -0.085509 1.035391 1.399378 -2.303834 8.207470 5.919410\n11890 42.745576 -0.160438 1.005684 1.433711 -2.256816 8.079988 5.875250\n11891 42.751889 -0.305808 0.959241 1.484500 -2.001382 7.804963 5.983390\n11892 42.757810 -0.369685 0.941905 1.499774 -1.896110 7.780083 6.080259\n11893 42.764019 -0.468901 0.924849 1.514290 -1.851309 7.855170 6.082345\n11894 42.770090 -0.511219 0.925784 1.515265 -1.931285 7.896263 6.011075\n11895 42.775982 -0.584364 0.943854 1.510788 -2.135090 7.946151 5.704453\n11896 42.782005 -0.613773 0.961410 1.507271 -2.220994 7.953294 5.574925\n11897 42.788013 -0.659285 1.005508 1.499753 -2.287242 7.799106 5.492656\n11898 42.794097 -0.676380 1.030656 1.497198 -2.275748 7.671766 5.489564\n11899 42.800479 -0.698169 1.084347 1.500334 -2.304718 7.569096 5.470103\n11900 42.806281 -0.707393 1.111379 1.506632 -2.380450 7.589010 5.456924\n11901 42.812359 -0.734333 1.163680 1.526421 -2.634964 7.600731 5.425468\n11902 42.818371 -0.753715 1.188823 1.537271 -2.762731 7.576815 5.442430\n11903 42.824278 -0.804942 1.231903 1.554324 -2.834094 7.584820 5.560043\n11904 42.830468 -0.833677 1.247668 1.563160 -2.719337 7.640055 5.623433\n11905 42.836497 -0.895001 1.264958 1.593675 -2.341702 7.777457 5.735338\n11906 42.842361 -0.931578 1.266942 1.615601 -2.140722 7.787359 5.772892\n11907 42.848510 -1.021085 1.261463 1.664591 -1.815932 7.634429 5.801267\n11908 42.854397 -1.074832 1.254537 1.689658 -1.680333 7.518447 5.841050\n11909 42.860579 -1.198164 1.233069 1.741586 -1.365906 7.339228 5.986515\n11910 42.866533 -1.266593 1.220753 1.769076 -1.212409 7.309981 6.134912\n11911 42.872677 -1.412892 1.196401 1.829656 -1.084260 7.411182 6.442851\n11912 42.878671 -1.484455 1.185914 1.861293 -1.096188 7.470041 6.458786\n11913 42.884661 -1.622491 1.169656 1.921975 -1.235317 7.473851 6.394053\n11914 42.890776 -1.688658 1.163657 1.951022 -1.327313 7.447685 6.331021\n11915 42.896805 -1.796395 1.160177 2.009988 -1.564551 7.474279 6.179819\n11916 42.902908 -1.834064 1.161825 2.038987 -1.778231 7.504999 6.113108\n11917 42.908830 -1.875511 1.170749 2.089027 -2.398514 7.560420 5.894268\n11918 42.914930 -1.879483 1.178331 2.106765 -2.627261 7.511999 5.769002\n11919 42.921093 -1.863478 1.193760 2.122991 -2.758881 7.366560 5.758921\n11920 42.927084 -1.844436 1.200456 2.121810 -2.678407 7.316839 5.849869\n11921 42.933339 -1.786119 1.213619 2.103435 -2.343134 7.190691 6.179217\n11922 42.939053 -1.752000 1.217994 2.088625 -2.147722 7.027442 6.359867\n11923 42.945287 -1.685176 1.222299 2.049849 -1.842927 6.565613 6.680454\n11924 42.951094 -1.654428 1.222277 2.024596 -1.734288 6.348208 6.847303\n11925 42.957333 -1.601617 1.216223 1.966057 -1.558061 5.977036 7.174119\n11926 42.963253 -1.580336 1.210427 1.934641 -1.484614 5.825593 7.314615\n11927 42.969253 -1.553684 1.194167 1.872861 -1.359219 5.607777 7.525035\n11928 42.975291 -1.548053 1.183514 1.842760 -1.296540 5.509665 7.612789\n11929 42.981322 -1.552412 1.157798 1.783845 -1.105940 5.231748 7.769647\n11930 42.987908 -1.561103 1.143241 1.756040 -0.988174 5.112788 7.858507\n11931 42.993403 -1.591686 1.112432 1.711797 -0.762376 5.156170 7.908335\n11932 42.999947 -1.638929 1.081038 1.688631 -0.579421 5.500157 7.834439\n11933 43.005660 -1.666882 1.063986 1.682107 -0.600388 5.747141 7.853204\n11934 43.012229 -1.721934 1.031556 1.658428 -1.038623 6.375398 8.023150\n11935 43.017737 -1.745873 1.016993 1.632026 -1.324088 6.567806 8.032990\n11936 43.024230 -1.792198 0.982628 1.551986 -1.805328 6.457900 7.740552\n11937 43.029750 -1.826102 0.953134 1.486037 -2.018866 6.181976 7.477734\n11938 43.036029 -1.873096 0.901972 1.380499 -2.214794 5.818848 7.375690\n11939 43.041805 -1.896421 0.867259 1.317370 -2.268777 5.634137 7.469473\n11940 43.048133 -1.941142 0.770949 1.165657 -2.206995 5.158741 7.756952\n11941 43.053795 -1.960324 0.718921 1.089016 -2.143305 4.932910 7.853115\n11942 43.060012 -2.005058 0.596336 0.917560 -1.968160 4.526635 7.986129\n11943 43.065957 -2.029698 0.526184 0.826670 -1.836218 4.356202 8.093204\n11944 43.072330 -2.071930 0.372133 0.648755 -1.485205 4.082504 8.454281\n11945 43.077906 -2.084074 0.289741 0.564789 -1.286931 3.939934 8.674627\n11946 43.084147 -2.081506 0.116197 0.403928 -0.917364 3.556412 9.112582\n11947 43.090132 -2.066788 0.026079 0.324718 -0.764048 3.351183 9.289473\n11948 43.096194 -2.017282 -0.157071 0.168496 -0.515931 3.098773 9.493603\n11949 43.102329 -1.985643 -0.247457 0.092035 -0.407152 3.077948 9.541430\n11950 43.108297 -1.914150 -0.420123 -0.055384 -0.220741 3.164704 9.604597\n11951 43.114316 -1.874834 -0.499105 -0.124352 -0.140158 3.218645 9.532826\n11952 43.120248 -1.790807 -0.635393 -0.249932 -0.049763 3.297130 9.410865\n11953 43.126238 -1.743912 -0.691872 -0.307786 -0.052097 3.414509 9.429714\n11954 43.132600 -1.640823 -0.772269 -0.421598 -0.227341 3.863397 9.647138\n11955 43.138355 -1.586242 -0.795613 -0.480109 -0.363174 4.090701 9.744893\n11956 43.144450 -1.482152 -0.813493 -0.603207 -0.699086 4.396966 9.633011\n11957 43.150476 -1.435085 -0.807555 -0.666264 -0.857047 4.468568 9.468661\n11958 43.156542 -1.346594 -0.769831 -0.791020 -1.037756 4.452690 9.142839\n11959 43.162533 -1.301030 -0.739235 -0.850317 -1.049310 4.378198 8.999337\n11960 43.168562 -1.199983 -0.658827 -0.961313 -0.991683 4.106785 8.729079\n11961 43.174536 -1.147176 -0.612230 -1.014528 -0.976824 3.950480 8.568587\n11962 43.180697 -1.052869 -0.512924 -1.116588 -1.043371 3.695562 8.261518\n11963 43.186610 -1.015588 -0.462096 -1.166210 -1.106481 3.628569 8.169156\n11964 43.192840 -0.962254 -0.361891 -1.262125 -1.208961 3.623154 8.094205\n11965 43.198921 -0.942610 -0.313775 -1.306610 -1.221645 3.646809 8.126120\n11966 43.204679 -0.906065 -0.224079 -1.386480 -1.137834 3.601289 8.283320\n11967 43.210829 -0.886598 -0.183897 -1.421674 -1.026734 3.500374 8.370008\n11968 43.216770 -0.842984 -0.111586 -1.480448 -0.726386 3.227867 8.561996\n11969 43.223070 -0.821080 -0.077752 -1.503113 -0.576633 3.101786 8.656441\n11970 43.228894 -0.783938 -0.013299 -1.533924 -0.356910 2.940213 8.807092\n11971 43.234995 -0.769047 0.017023 -1.542578 -0.305901 2.891417 8.857380\n11972 43.241086 -0.737833 0.071340 -1.548416 -0.351563 2.877178 8.950360\n11973 43.246968 -0.716995 0.094077 -1.546598 -0.442569 2.940319 9.014493\n11974 43.253146 -0.662869 0.128797 -1.535957 -0.707600 3.219739 9.084847\n11975 43.259251 -0.629543 0.139741 -1.528718 -0.870158 3.359689 9.060998\n11976 43.265367 -0.558886 0.146656 -1.512490 -1.164542 3.501781 8.939412\n11977 43.271308 -0.524843 0.141166 -1.504843 -1.252289 3.529701 8.904533\n11978 43.277332 -0.461542 0.112947 -1.489674 -1.294930 3.534878 8.926095\n11979 43.283467 -0.430292 0.091271 -1.480341 -1.261403 3.512834 8.942188\n11980 43.289286 -0.366426 0.035638 -1.456813 -1.178394 3.423641 8.960245\n11981 43.295309 -0.334677 0.003911 -1.441934 -1.160599 3.387633 8.977984\n11982 43.301423 -0.278516 -0.060737 -1.408962 -1.166012 3.335966 9.061818\n11983 43.307624 -0.255737 -0.091562 -1.392741 -1.185525 3.290256 9.094380\n11984 43.313554 -0.224068 -0.147839 -1.361073 -1.230236 3.143216 9.053033\n11985 43.319549 -0.214562 -0.173732 -1.344906 -1.243281 3.057237 8.990731\n11986 43.325544 -0.200704 -0.222182 -1.309224 -1.278343 2.869649 8.852435\n11987 43.331733 -0.194178 -0.244756 -1.289155 -1.283206 2.771344 8.799154\n11988 43.337692 -0.179356 -0.285562 -1.247475 -1.268608 2.580070 8.753793\n11989 43.343868 -0.174482 -0.299627 -1.232757 -1.273445 2.529522 8.759571\n11990 43.349775 -0.168106 -0.336685 -1.201030 -1.324252 2.474478 8.813439\n11991 43.355772 -0.169434 -0.352861 -1.191756 -1.330872 2.486597 8.880608\n11992 43.361832 -0.177337 -0.378449 -1.183069 -1.252067 2.573778 9.072487\n11993 43.368011 -0.181127 -0.388318 -1.181694 -1.185236 2.623123 9.160028\n11994 43.374029 -0.183073 -0.403570 -1.177462 -1.048266 2.660513 9.257270\n11995 43.379844 -0.181645 -0.408670 -1.173247 -0.971708 2.637590 9.267330\n11996 43.386015 -0.177219 -0.413330 -1.158035 -0.831192 2.554536 9.256248\n11997 43.392051 -0.174714 -0.412823 -1.147123 -0.768873 2.532792 9.268914\n11998 43.398190 -0.170278 -0.407755 -1.120885 -0.681320 2.520942 9.351745\n11999 43.404167 -0.167777 -0.403593 -1.104521 -0.663051 2.516282 9.398171\n12000 43.410241 -0.161817 -0.391447 -1.063871 -0.649603 2.485619 9.454833\n12001 43.416234 -0.158084 -0.384119 -1.040082 -0.649263 2.445967 9.467555\n12002 43.422378 -0.153434 -0.369398 -0.990599 -0.678809 2.273479 9.515178\n12003 43.428780 -0.152902 -0.362038 -0.966647 -0.698481 2.143402 9.525380\n12004 43.434420 -0.157159 -0.347320 -0.921954 -0.690250 1.885665 9.638634\n12005 43.440878 -0.170104 -0.331786 -0.880005 -0.594967 1.715501 9.869561\n12006 43.446429 -0.177982 -0.323390 -0.858943 -0.512761 1.671760 9.963000\n12007 43.452814 -0.197905 -0.306058 -0.814923 -0.356618 1.595224 10.057639\n12008 43.458465 -0.211028 -0.296605 -0.792954 -0.336744 1.536348 10.077426\n12009 43.465200 -0.240008 -0.276161 -0.754310 -0.415549 1.406617 10.097615\n12010 43.470544 -0.254473 -0.265426 -0.738236 -0.468157 1.348654 10.099526\n12011 43.476823 -0.279475 -0.244100 -0.709891 -0.580037 1.283284 10.032969\n12012 43.482802 -0.288446 -0.233647 -0.696294 -0.632971 1.299887 9.977731\n12013 43.488740 -0.296439 -0.214336 -0.668726 -0.686159 1.412443 9.829465\n12014 43.494800 -0.295969 -0.206079 -0.655065 -0.701824 1.483207 9.757113\n12015 43.500920 -0.286292 -0.194808 -0.632678 -0.727283 1.620214 9.679232\n12016 43.506793 -0.277025 -0.191514 -0.625694 -0.727246 1.681122 9.684522\n12017 43.512921 -0.252068 -0.188701 -0.619233 -0.725609 1.789984 9.709159\n12018 43.518912 -0.237754 -0.188685 -0.618192 -0.731045 1.845028 9.695400\n12019 43.524914 -0.209596 -0.190664 -0.615700 -0.695799 1.928714 9.671647\n12020 43.530944 -0.196814 -0.191346 -0.612713 -0.662392 1.933219 9.670055\n12021 43.537153 -0.176037 -0.192514 -0.603894 -0.577685 1.860687 9.652060\n12022 43.543020 -0.169137 -0.193571 -0.599226 -0.548967 1.812046 9.642245\n12023 43.549023 -0.165218 -0.196008 -0.590480 -0.540139 1.747363 9.635215\n12024 43.555263 -0.167968 -0.196224 -0.586587 -0.564817 1.744583 9.649596\n12025 43.561170 -0.182110 -0.194141 -0.578013 -0.695051 1.773813 9.665027\n12026 43.567083 -0.193453 -0.191555 -0.573164 -0.765988 1.780982 9.638453\n12027 43.573241 -0.221696 -0.186018 -0.563285 -0.825171 1.730727 9.553198\n12028 43.579352 -0.237094 -0.184887 -0.559490 -0.829341 1.688395 9.522977\n12029 43.585496 -0.263052 -0.187240 -0.556318 -0.822001 1.658013 9.510346\n12030 43.591294 -0.271894 -0.190672 -0.557605 -0.798454 1.673562 9.514982\n12031 43.597577 -0.285264 -0.201909 -0.563436 -0.705999 1.762874 9.555202\n12032 43.603470 -0.290228 -0.209071 -0.567113 -0.620873 1.796900 9.579912\n12033 43.609428 -0.296284 -0.223337 -0.575866 -0.416878 1.789826 9.697410\n12034 43.615651 -0.299226 -0.230914 -0.580435 -0.341347 1.763733 9.773417\n12035 43.621547 -0.304823 -0.245507 -0.588787 -0.319730 1.707951 9.821693\n12036 43.627667 -0.304972 -0.250995 -0.592761 -0.369114 1.680053 9.797855\n12037 43.633594 -0.300852 -0.257666 -0.600893 -0.515546 1.576534 9.701290\n12038 43.639650 -0.297193 -0.259271 -0.605525 -0.602343 1.521548 9.633607\n12039 43.646009 -0.285646 -0.260692 -0.617456 -0.760516 1.467314 9.516906\n12040 43.651689 -0.278507 -0.261525 -0.624637 -0.814717 1.458257 9.492680\n12041 43.657677 -0.259511 -0.263179 -0.642315 -0.816688 1.423905 9.421920\n12042 43.663819 -0.248667 -0.264058 -0.653510 -0.821499 1.394347 9.425093\n12043 43.670001 -0.229094 -0.268780 -0.681312 -0.869287 1.330705 9.522666\n12044 43.675947 -0.217676 -0.271544 -0.697918 -0.883455 1.277608 9.546134\n12045 43.682035 -0.193335 -0.278754 -0.730487 -0.874854 1.165106 9.564988\n12046 43.687861 -0.185914 -0.284216 -0.745139 -0.854613 1.118731 9.547446\n12047 43.693981 -0.173251 -0.293993 -0.767682 -0.807924 1.110825 9.500886\n12048 43.700142 -0.166540 -0.296598 -0.774573 -0.808808 1.146350 9.530086\n12049 43.706358 -0.158319 -0.298918 -0.781940 -0.869968 1.245799 9.652135\n12050 43.712264 -0.153328 -0.298227 -0.785364 -0.886978 1.256621 9.688303\n12051 43.718273 -0.140457 -0.295611 -0.791080 -0.884677 1.165520 9.761501\n12052 43.724357 -0.134018 -0.294350 -0.791467 -0.917156 1.087019 9.734020\n12053 43.730419 -0.112060 -0.285246 -0.781477 -1.139559 1.023616 9.654407\n12054 43.736541 -0.096078 -0.277003 -0.770105 -1.326495 1.044245 9.670036\n12055 43.742316 -0.054995 -0.257026 -0.739410 -1.647747 1.010560 9.699919\n12056 43.748543 -0.027465 -0.245733 -0.723888 -1.724408 0.898194 9.668200\n12057 43.754403 0.035656 -0.226885 -0.691589 -1.718879 0.662745 9.522088\n12058 43.760400 0.066060 -0.220027 -0.672836 -1.704176 0.625615 9.445726\n12059 43.766525 0.123804 -0.208256 -0.623739 -1.709559 0.768057 9.436426\n12060 43.772526 0.152619 -0.202823 -0.592118 -1.647256 0.826407 9.467947\n12061 43.778533 0.198982 -0.194514 -0.519929 -1.416074 0.857648 9.537827\n12062 43.784525 0.209870 -0.192828 -0.483688 -1.317127 0.900996 9.571156\n12063 43.790687 0.209545 -0.191814 -0.416532 -1.150094 1.002239 9.590858\n12064 43.796830 0.201778 -0.191665 -0.385828 -1.055997 1.008620 9.574253\n12065 43.802963 0.166181 -0.193254 -0.329337 -1.041915 1.072710 9.602252\n12066 43.808808 0.142202 -0.194148 -0.304659 -1.118982 1.147730 9.630418\n12067 43.814813 0.098745 -0.193894 -0.265793 -1.316351 1.157359 9.584868\n12068 43.820968 0.073209 -0.194908 -0.251620 -1.442902 1.111676 9.549756\n12069 43.826949 0.015364 -0.199504 -0.240632 -1.591476 0.915668 9.471758\n12070 43.832938 -0.015206 -0.202426 -0.243422 -1.603096 0.855052 9.602410\n12071 43.838903 -0.075192 -0.215588 -0.253698 -1.434041 0.737179 9.982294\n12072 43.844971 -0.103280 -0.224680 -0.257746 -1.312055 0.675865 10.162581\n12073 43.851017 -0.153747 -0.247763 -0.258129 -1.197513 0.583006 10.341626\n12074 43.857799 -0.194493 -0.272123 -0.252488 -1.311265 0.472290 10.156220\n12075 43.863236 -0.211682 -0.283358 -0.250366 -1.431257 0.466466 10.055089\n12076 43.869627 -0.231403 -0.307937 -0.249771 -1.636983 0.607251 9.856791\n12077 43.875197 -0.227164 -0.325390 -0.251225 -1.658155 0.714762 9.753507\n12078 43.881750 -0.202587 -0.362348 -0.253533 -1.485214 0.758515 9.633086\n12079 43.887291 -0.185998 -0.382970 -0.254423 -1.354439 0.757245 9.565884\n12080 43.893821 -0.153990 -0.424934 -0.255775 -1.112768 0.845253 9.579200\n12081 43.899325 -0.140261 -0.446073 -0.256750 -1.030456 0.885467 9.569662\n12082 43.905818 -0.119302 -0.486435 -0.261474 -0.953771 0.921146 9.462824\n12083 43.911477 -0.114417 -0.507896 -0.265184 -0.935336 0.918303 9.351508\n12084 43.918226 -0.113594 -0.551118 -0.272388 -0.920999 0.949960 9.158529\n12085 43.923572 -0.118337 -0.568653 -0.274417 -0.917267 0.966929 9.203313\n12086 43.930037 -0.144997 -0.587861 -0.271671 -0.865022 0.862644 9.464096\n12087 43.935592 -0.160476 -0.585444 -0.268100 -0.843752 0.783023 9.469064\n12088 43.941933 -0.205791 -0.561003 -0.258936 -0.847287 0.693692 9.293432\n12089 43.947734 -0.238233 -0.541875 -0.253481 -0.818494 0.628603 9.207202\n12090 43.953927 -0.306329 -0.491961 -0.240869 -0.661421 0.604542 9.346889\n12091 43.959723 -0.332907 -0.462010 -0.234025 -0.562192 0.662902 9.502112\n12092 43.966129 -0.368774 -0.395722 -0.220102 -0.419617 0.734060 9.729853\n12093 43.971839 -0.382404 -0.360366 -0.212522 -0.398885 0.690582 9.732053\n12094 43.978192 -0.417556 -0.285794 -0.194384 -0.413352 0.609785 9.768689\n12095 43.983847 -0.436172 -0.245448 -0.183487 -0.418959 0.616389 9.811208\n12096 43.989999 -0.456281 -0.157712 -0.156872 -0.355875 0.647028 9.909130\n12097 43.996038 -0.460150 -0.114933 -0.139896 -0.311444 0.640996 9.925816\n12098 44.002287 -0.455009 -0.034734 -0.100146 -0.291143 0.554807 9.765621\n12099 44.008039 -0.446171 0.002680 -0.079490 -0.303543 0.499542 9.718835\n12100 44.014295 -0.425909 0.065424 -0.040033 -0.309189 0.404596 9.678374\n12101 44.019985 -0.416771 0.090948 -0.022602 -0.308855 0.374664 9.695287\n12102 44.026302 -0.395176 0.130637 0.006836 -0.360617 0.369172 9.821331\n12103 44.032106 -0.383958 0.143387 0.018512 -0.396999 0.380134 9.885123\n12104 44.038501 -0.359760 0.154188 0.032048 -0.433276 0.314819 9.963099\n12105 44.044388 -0.346787 0.152032 0.033998 -0.434669 0.261522 10.043620\n12106 44.050379 -0.326867 0.136898 0.030199 -0.449725 0.219173 10.252636\n12107 44.056300 -0.317070 0.126429 0.026215 -0.433635 0.197255 10.324813\n12108 44.062462 -0.303407 0.101570 0.017047 -0.413899 0.127118 10.485404\n12109 44.068353 -0.301725 0.086483 0.012408 -0.400613 0.096345 10.529746\n12110 44.074470 -0.298229 0.053541 0.003713 -0.371376 0.089134 10.573668\n12111 44.080357 -0.290795 0.032907 0.000067 -0.291527 0.177034 10.542210\n12112 44.086517 -0.275813 -0.017941 -0.005909 -0.188141 0.353482 10.563650\n12113 44.092348 -0.266444 -0.046141 -0.008911 -0.169636 0.310245 10.666733\n12114 44.098713 -0.248558 -0.102044 -0.018696 -0.163369 0.146518 10.926168\n12115 44.104600 -0.241944 -0.128457 -0.024441 -0.193855 0.073189 10.965761\n12116 44.110769 -0.232773 -0.176974 -0.032514 -0.221058 -0.124686 10.991172\n12117 44.116499 -0.227282 -0.199156 -0.035377 -0.210926 -0.242556 11.009615\n12118 44.122784 -0.207012 -0.238636 -0.039561 -0.151920 -0.391843 11.090912\n12119 44.128916 -0.190205 -0.256005 -0.041037 -0.128516 -0.408322 11.123393\n12120 44.134706 -0.144928 -0.285496 -0.045223 -0.099677 -0.306998 11.130803\n12121 44.140728 -0.118627 -0.296965 -0.047388 -0.057850 -0.210684 11.102293\n12122 44.146879 -0.070487 -0.316010 -0.046194 0.167788 0.014906 11.125911\n12123 44.152772 -0.048912 -0.325247 -0.042637 0.322042 0.131805 11.155012\n12124 44.159051 -0.007910 -0.343838 -0.034253 0.540646 0.293147 11.208240\n12125 44.164895 0.011079 -0.353977 -0.030571 0.591077 0.309073 11.188603\n12126 44.171035 0.034414 -0.375797 -0.028359 0.558538 0.256576 11.045440\n12127 44.176991 0.038771 -0.385600 -0.030788 0.513539 0.210724 10.972017\n12128 44.183133 0.031041 -0.398496 -0.044069 0.402707 0.122728 10.920565\n12129 44.189301 0.020629 -0.401109 -0.053831 0.333406 0.096062 10.884891\n12130 44.195228 -0.007641 -0.398925 -0.077383 0.260495 0.089931 10.765118\n12131 44.201322 -0.022204 -0.392611 -0.090494 0.277576 0.111013 10.670251\n12132 44.207309 -0.050086 -0.365371 -0.114026 0.446097 0.163251 10.605978\n12133 44.213290 -0.063040 -0.345559 -0.123080 0.562280 0.198800 10.611176\n12134 44.219302 -0.078500 -0.291697 -0.136780 0.721585 0.275572 10.556308\n12135 44.225250 -0.080377 -0.257645 -0.141776 0.724761 0.303632 10.494007\n12136 44.232130 -0.085336 -0.177461 -0.147578 0.745866 0.218961 10.377400\n12137 44.237413 -0.084963 -0.132041 -0.148367 0.741096 0.172102 10.316113\n12138 44.243648 -0.071223 -0.032007 -0.143845 0.757855 0.125411 10.289145\n12139 44.249617 -0.060846 0.018178 -0.139475 0.766001 0.113215 10.286329\n12140 44.255670 -0.030464 0.125974 -0.127006 0.720860 0.089951 10.189815\n12141 44.261622 -0.015463 0.169964 -0.122926 0.685866 0.100544 10.200730\n12142 44.267607 0.007729 0.243880 -0.119354 0.659517 0.174399 10.314006\n12143 44.273603 0.019700 0.272849 -0.119219 0.735608 0.224101 10.381371\n12144 44.279836 0.048814 0.307699 -0.119658 0.973462 0.311856 10.507978\n12145 44.285618 0.060483 0.311271 -0.120796 1.007096 0.283091 10.571604\n12146 44.291779 0.081803 0.296350 -0.130633 0.869706 0.085738 10.630092\n12147 44.297762 0.093653 0.280767 -0.140992 0.742242 0.006536 10.616589\n12148 44.303858 0.110640 0.235533 -0.167665 0.518982 -0.108004 10.553817\n12149 44.309957 0.115618 0.207968 -0.181893 0.420246 -0.191093 10.557347\n12150 44.315971 0.132496 0.147140 -0.211865 0.253552 -0.283248 10.613143\n12151 44.322068 0.141833 0.115472 -0.225708 0.180234 -0.322875 10.662889\n12152 44.328075 0.156779 0.050376 -0.247659 0.142955 -0.391513 10.800550\n12153 44.334074 0.164185 0.019776 -0.254939 0.169827 -0.392193 10.860619\n12154 44.340213 0.178149 -0.037930 -0.257400 0.233902 -0.302053 10.911326\n12155 44.346589 0.184375 -0.065898 -0.252053 0.271573 -0.235603 10.869283\n12156 44.352287 0.197511 -0.119153 -0.232531 0.358551 -0.111093 10.720778\n12157 44.358619 0.217503 -0.168299 -0.208824 0.438939 -0.069084 10.557263\n12158 44.364319 0.229574 -0.189644 -0.199838 0.475352 -0.105804 10.463458\n12159 44.370878 0.255589 -0.226372 -0.192088 0.427602 -0.185787 10.284928\n12160 44.376380 0.264996 -0.242362 -0.193539 0.393011 -0.206290 10.265585\n12161 44.383009 0.271146 -0.272062 -0.206380 0.383582 -0.160220 10.487654\n12162 44.388645 0.269107 -0.284946 -0.216408 0.436722 -0.113562 10.644670\n12163 44.394978 0.253173 -0.304595 -0.239490 0.593455 -0.020688 10.962047\n12164 44.400646 0.242143 -0.310076 -0.251054 0.633150 0.040894 11.064528\n12165 44.406736 0.208873 -0.304259 -0.269656 0.723872 0.069422 11.127335\n12166 44.412682 0.189347 -0.294377 -0.275656 0.778383 0.040169 11.055333\n12167 44.418774 0.155146 -0.265909 -0.277221 0.806527 -0.021183 10.810437\n12168 44.424569 0.143614 -0.248337 -0.272208 0.760385 0.001600 10.733290\n12169 44.430887 0.132046 -0.208180 -0.251110 0.631299 0.117854 10.625590\n12170 44.436672 0.132542 -0.185491 -0.236073 0.585430 0.162552 10.556134\n12171 44.443064 0.145848 -0.138020 -0.203540 0.543517 0.184961 10.399055\n12172 44.448767 0.155978 -0.115058 -0.188686 0.570442 0.184382 10.380141\n12173 44.454998 0.177148 -0.071553 -0.159659 0.696746 0.268349 10.465333\n12174 44.461067 0.189916 -0.049949 -0.144006 0.753632 0.358825 10.489984\n12175 44.466954 0.216880 -0.008465 -0.111440 0.757078 0.608744 10.527492\n12176 44.472862 0.225421 0.012185 -0.096251 0.750551 0.675625 10.489390\n12177 44.478945 0.229497 0.055544 -0.072728 0.717416 0.673800 10.360967\n12178 44.485121 0.225523 0.076003 -0.065051 0.663390 0.645203 10.313009\n12179 44.491251 0.211239 0.106240 -0.060594 0.481755 0.603626 10.170115\n12180 44.497135 0.196545 0.113254 -0.062831 0.417022 0.577887 10.087755\n12181 44.503341 0.169493 0.105720 -0.067509 0.381239 0.571993 9.928281\n12182 44.509351 0.152249 0.092009 -0.067987 0.397528 0.567027 9.893960\n12183 44.515394 0.117231 0.047356 -0.069691 0.406454 0.520764 9.954270\n12184 44.521513 0.101383 0.017956 -0.071551 0.391497 0.489994 10.049128\n12185 44.527764 0.058854 -0.051229 -0.077371 0.482025 0.414068 10.377482\n12186 44.533259 0.034340 -0.090645 -0.079591 0.504228 0.447967 10.542561\n12187 44.539426 -0.015557 -0.169075 -0.074404 0.494833 0.576683 10.644253\n12188 44.545354 -0.038138 -0.207613 -0.066874 0.494998 0.627410 10.653231\n12189 44.551653 -0.081121 -0.279153 -0.043644 0.491726 0.721749 10.566051\n12190 44.557516 -0.097084 -0.306948 -0.030735 0.529650 0.712994 10.540587\n12191 44.563565 -0.119074 -0.346720 -0.007530 0.689561 0.549810 10.529423\n12192 44.569455 -0.133658 -0.359338 0.004314 0.753500 0.446937 10.537050\n12193 44.575604 -0.160230 -0.367572 0.032548 0.784069 0.445773 10.622480\n12194 44.581680 -0.174974 -0.363063 0.048704 0.793172 0.522476 10.694454\n12195 44.587697 -0.215387 -0.339975 0.083643 0.876269 0.567121 10.886471\n12196 44.593808 -0.231462 -0.321287 0.098679 0.886739 0.585428 10.885180\n12197 44.599777 -0.251510 -0.271114 0.114831 1.031281 0.443190 10.867650\n12198 44.605946 -0.265418 -0.238110 0.116991 1.134469 0.345649 10.863687\n12199 44.611920 -0.276235 -0.176913 0.115455 1.188274 0.323287 10.758620\n12200 44.617767 -0.274377 -0.143205 0.112894 1.174892 0.350258 10.784330\n12201 44.623915 -0.263133 -0.075387 0.108911 1.128933 0.256724 10.657160\n12202 44.630055 -0.264371 -0.040019 0.108477 1.154483 0.239591 10.706736\n12203 44.636013 -0.268155 0.029602 0.105840 1.095396 0.416864 10.920341\n12204 44.642201 -0.256552 0.068536 0.101808 1.006398 0.474183 10.877036\n12205 44.648026 -0.208818 0.153528 0.091697 0.874268 0.318422 10.602571\n12206 44.654004 -0.188773 0.194130 0.087854 0.808188 0.237386 10.396382\n12207 44.660197 -0.132591 0.271356 0.090799 0.674504 0.287913 10.042501\n12208 44.666197 -0.087722 0.306080 0.098338 0.652570 0.343887 10.013126\n12209 44.672418 0.015716 0.354891 0.117340 0.565611 0.293435 9.904691\n12210 44.678255 0.065149 0.368422 0.124678 0.492225 0.228008 9.825252\n12211 44.684292 0.159600 0.372349 0.127601 0.371622 0.208011 9.753764\n12212 44.690288 0.203820 0.364251 0.124479 0.328377 0.224148 9.714912\n12213 44.696382 0.282389 0.333874 0.120000 0.244861 0.354142 9.691720\n12214 44.702453 0.319562 0.313105 0.120054 0.145713 0.511458 9.698653\n12215 44.708458 0.366136 0.265988 0.120904 0.083370 0.544790 9.668093\n12216 44.714453 0.373675 0.238456 0.119259 0.096784 0.439090 9.662741\n12217 44.720582 0.369655 0.176319 0.110450 0.084461 0.208181 9.677286\n12218 44.726591 0.357641 0.141981 0.103625 0.034800 0.172553 9.740036\n12219 44.732757 0.315768 0.065992 0.096292 -0.085725 0.408466 9.905507\n12220 44.738723 0.284669 0.026476 0.100395 -0.098684 0.575215 10.007824\n12221 44.744749 0.190743 -0.060965 0.116396 -0.010414 0.685622 10.427589\n12222 44.750787 0.122560 -0.112496 0.123093 0.028278 0.673899 10.564100\n12223 44.756843 -0.036089 -0.227550 0.134696 0.242059 0.695663 10.494872\n12224 44.762948 -0.117475 -0.287517 0.143727 0.387347 0.757627 10.348345\n12225 44.768945 -0.259350 -0.396184 0.176125 0.391686 0.867055 10.048876\n12226 44.774923 -0.307818 -0.436741 0.198515 0.307046 0.842051 9.937476\n12227 44.780957 -0.372841 -0.484839 0.243744 0.209667 0.624253 9.756251\n12228 44.786982 -0.401542 -0.495456 0.264970 0.207073 0.525614 9.622324\n12229 44.793211 -0.453879 -0.488407 0.307527 0.237023 0.536046 9.416064\n12230 44.799051 -0.469885 -0.472231 0.329001 0.259331 0.621515 9.434169\n12231 44.805180 -0.469250 -0.423573 0.370403 0.325053 0.668986 9.665524\n12232 44.811218 -0.456244 -0.394756 0.387716 0.353848 0.596235 9.826156\n12233 44.817315 -0.429693 -0.337656 0.410514 0.401445 0.445901 9.987635\n12234 44.823839 -0.433668 -0.284872 0.427670 0.493979 0.328675 10.015097\n12235 44.829198 -0.445101 -0.259331 0.441163 0.577585 0.248349 10.002711\n12236 44.835591 -0.457871 -0.208831 0.480993 0.717938 0.214362 9.968596\n12237 44.841263 -0.457886 -0.186434 0.504489 0.782492 0.153748 9.997654\n12238 44.847783 -0.455147 -0.150833 0.546299 0.895237 -0.015887 10.064777\n12239 44.853468 -0.454222 -0.136625 0.561728 0.883850 -0.017274 10.081621\n12240 44.859833 -0.463200 -0.111440 0.583640 0.857804 0.123128 10.056666\n12241 44.865535 -0.475110 -0.098583 0.592597 0.920783 0.187780 10.036428\n12242 44.871884 -0.503990 -0.073745 0.612626 1.135836 0.236830 10.057651\n12243 44.877758 -0.512151 -0.061407 0.622709 1.213346 0.202861 10.048232\n12244 44.883929 -0.506103 -0.037309 0.636330 1.163177 0.069174 9.912181\n12245 44.889644 -0.495633 -0.027200 0.640352 1.047551 0.018065 9.822722\n12246 44.895801 -0.463293 -0.012261 0.646804 0.806334 -0.034927 9.713493\n12247 44.901609 -0.440656 -0.008650 0.650469 0.693408 -0.035482 9.739656\n12248 44.907882 -0.398678 -0.015976 0.660348 0.493335 -0.042314 9.933990\n12249 44.914030 -0.380944 -0.027793 0.664752 0.422780 -0.116997 10.018455\n12250 44.919702 -0.350944 -0.067782 0.667040 0.369903 -0.339892 10.116359\n12251 44.925936 -0.338628 -0.096386 0.664805 0.383477 -0.431290 10.115553\n12252 44.931918 -0.313108 -0.166503 0.654784 0.460433 -0.510153 10.020804\n12253 44.938049 -0.300507 -0.207661 0.647831 0.490642 -0.498018 9.972443\n12254 44.944248 -0.288633 -0.296801 0.633543 0.538381 -0.413756 9.839656\n12255 44.949954 -0.290881 -0.340798 0.626823 0.591897 -0.356912 9.797990\n12256 44.956122 -0.308706 -0.421028 0.613769 0.877648 -0.206250 9.893532\n12257 44.962115 -0.320205 -0.454363 0.607613 1.111626 -0.129850 10.000689\n12258 44.968174 -0.333149 -0.503411 0.594392 1.586684 -0.005733 10.180201\n12259 44.974315 -0.334502 -0.518497 0.585898 1.731591 0.030447 10.198277\n12260 44.980134 -0.344696 -0.531912 0.563554 1.815360 0.075443 10.146104\n12261 44.986265 -0.354062 -0.530642 0.550379 1.822730 0.092683 10.143605\n12262 44.992268 -0.371662 -0.513402 0.521408 1.862269 0.095006 10.277124\n12263 44.998289 -0.378990 -0.499524 0.506938 1.923085 0.057967 10.437420\n12264 45.004586 -0.389525 -0.465399 0.475533 2.142343 -0.220401 11.042062\n12265 45.010456 -0.396252 -0.443134 0.457122 2.264825 -0.425390 11.503564\n12266 45.016572 -0.407481 -0.382312 0.414620 2.543683 -0.774832 12.475381\n12267 45.022452 -0.411180 -0.344368 0.391591 2.691464 -0.912906 12.839567\n12268 45.028579 -0.417386 -0.261499 0.345881 2.835806 -1.118825 12.951371\n12269 45.034825 -0.414984 -0.220732 0.324259 2.783864 -1.202178 12.602752\n12270 45.040526 -0.376955 -0.142169 0.284683 2.363245 -1.212719 11.413519\n12271 45.046641 -0.334549 -0.103416 0.266735 2.068547 -1.086224 10.851199\n12272 45.052642 -0.204848 -0.022575 0.231475 1.686408 -0.724153 10.193582\n12273 45.058915 -0.127316 0.019799 0.212976 1.674717 -0.581602 10.159859\n12274 45.064805 0.012742 0.102336 0.171098 1.859774 -0.501656 10.454758\n12275 45.070737 0.064272 0.141716 0.147659 1.969923 -0.567335 10.651269\n12276 45.076809 0.123530 0.216652 0.102551 2.038393 -0.840323 10.940157\n12277 45.082898 0.137772 0.250551 0.083528 1.963853 -0.999501 10.982707\n12278 45.088875 0.165026 0.305194 0.054994 1.638325 -1.201294 10.971405\n12279 45.095021 0.172636 0.319836 0.042269 1.388530 -1.215704 11.060283\n12280 45.101026 0.168670 0.306469 0.015597 0.727825 -0.913180 10.876439\n12281 45.106990 0.158204 0.279227 0.004975 0.430148 -0.608935 10.513952\n12282 45.112988 0.096974 0.178975 -0.001206 0.296658 -0.214564 9.747557\n12283 45.119213 0.054638 0.109118 0.006167 0.335308 -0.158610 9.419018\n12284 45.125389 -0.016161 -0.045593 0.039675 0.334474 -0.220372 9.134995\n12285 45.131382 -0.055820 -0.148850 0.066336 0.295764 -0.305127 9.037898\n12286 45.137258 -0.147638 -0.310114 0.116303 0.244802 -0.325856 8.771152\n12287 45.143381 -0.206306 -0.383288 0.143791 0.317560 -0.238183 8.700246\n12288 45.149649 -0.337447 -0.509017 0.192881 0.659146 -0.070150 8.734751\n12289 45.155598 -0.407248 -0.559151 0.213158 0.834430 -0.100456 8.810538\n12290 45.161395 -0.543129 -0.631475 0.240545 1.066291 -0.207641 8.890230\n12291 45.167523 -0.606329 -0.653508 0.245537 1.055957 -0.166848 8.869311\n12292 45.173525 -0.715482 -0.673714 0.243164 0.963959 0.060704 8.757763\n12293 45.179553 -0.762002 -0.675609 0.238366 0.999376 0.172990 8.714607\n12294 45.185776 -0.842072 -0.674454 0.224075 1.162768 0.263043 8.758565\n12295 45.192278 -0.899237 -0.672837 0.205564 1.310495 0.101257 8.976386\n12296 45.197699 -0.920015 -0.672551 0.193513 1.399579 -0.045293 9.125253\n12297 45.204293 -0.938681 -0.670754 0.181035 1.475004 -0.190672 9.285530\n12298 45.209797 -0.969277 -0.654652 0.165853 1.559160 -0.375039 9.556994\n12299 45.216556 -0.983833 -0.596900 0.168927 1.610459 -0.647153 9.749863\n12300 45.221921 -0.976395 -0.532377 0.177535 1.600011 -0.843983 9.880614\n12301 45.228549 -0.944106 -0.340484 0.202646 1.603869 -1.271298 9.718925\n12302 45.234023 -0.927170 -0.225285 0.210257 1.577365 -1.493557 9.560682\n12303 45.240502 -0.875132 0.003026 0.209711 1.234164 -1.708201 9.360565\n12304 45.246069 -0.844662 0.099176 0.205707 1.069480 -1.654268 9.100189\n12305 45.252445 -0.792068 0.245905 0.202071 0.955093 -1.364687 8.971935\n12306 45.258164 -0.774169 0.299522 0.206538 0.957744 -1.248513 9.199833\n12307 45.264635 -0.752252 0.378995 0.221327 1.116075 -1.282621 10.326944\n12308 45.270094 -0.747231 0.404825 0.227377 1.270992 -1.415621 11.026019\n12309 45.276657 -0.736229 0.410852 0.240884 1.533213 -1.768800 11.716333\n12310 45.282269 -0.719853 0.381646 0.249667 1.594713 -1.861178 11.573812\n12311 45.288570 -0.645116 0.251956 0.267491 1.506894 -1.843626 11.284433\n12312 45.294317 -0.584375 0.162340 0.277241 1.405497 -1.870052 11.296597\n12313 45.300604 -0.419081 -0.024558 0.295260 1.307226 -2.141750 11.526578\n12314 45.306462 -0.323352 -0.107372 0.298719 1.250824 -2.285363 11.573315\n12315 45.312584 -0.133956 -0.226711 0.288773 1.048369 -2.357379 11.242403\n12316 45.318478 -0.047957 -0.257414 0.275509 1.003176 -2.236874 10.911611\n12317 45.324813 0.095015 -0.257371 0.242545 1.111023 -1.710503 10.305242\n12318 45.330540 0.144342 -0.229273 0.230760 1.224668 -1.441184 10.056188\n12319 45.336650 0.194488 -0.127365 0.220594 1.445493 -1.190105 9.849071\n12320 45.342635 0.203664 -0.060871 0.219504 1.507121 -1.213394 9.772068\n12321 45.348704 0.214427 0.083856 0.223221 1.568947 -1.451667 9.653179\n12322 45.354632 0.222328 0.152084 0.227784 1.594842 -1.599222 9.638450\n12323 45.360637 0.234815 0.266665 0.244240 1.603052 -1.790997 9.787045\n12324 45.366901 0.233359 0.309842 0.258337 1.607917 -1.837466 9.907852\n12325 45.372873 0.207389 0.366956 0.297702 1.647065 -1.825974 9.971156\n12326 45.378922 0.190893 0.381109 0.318733 1.615181 -1.758826 9.893555\n12327 45.384929 0.196481 0.389904 0.355220 1.471788 -1.511294 9.501145\n12328 45.390905 0.214342 0.388885 0.368643 1.385537 -1.423627 9.370316\n12329 45.397037 0.259838 0.378710 0.376013 1.077821 -1.463387 9.169791\n12330 45.402998 0.274206 0.375080 0.373974 0.927058 -1.495032 9.061975\n12331 45.409051 0.271457 0.366005 0.369096 0.935844 -1.383135 9.019170\n12332 45.414964 0.266380 0.361127 0.367549 1.019125 -1.242282 8.968130\n12333 45.421084 0.286279 0.358519 0.372766 1.123100 -1.071520 9.013169\n12334 45.427359 0.309123 0.358116 0.372911 1.118236 -1.096744 8.995408\n12335 45.433244 0.384182 0.364213 0.366533 1.167223 -1.076611 8.605417\n12336 45.439309 0.426303 0.371826 0.365997 1.323095 -1.015279 8.615855\n12337 45.445370 0.514101 0.389698 0.365079 1.772229 -1.017129 9.054170\n12338 45.451259 0.559791 0.402696 0.366762 1.912954 -1.085369 9.265918\n12339 45.457661 0.641166 0.428228 0.367385 1.950226 -1.358359 9.493665\n12340 45.463258 0.670873 0.437747 0.360440 1.879023 -1.524144 9.524947\n12341 45.469441 0.701760 0.456114 0.332714 1.746271 -1.868108 9.972694\n12342 45.475479 0.704572 0.460389 0.307733 1.748993 -2.087004 10.391914\n12343 45.481587 0.682057 0.448914 0.238338 1.729650 -2.412954 10.908193\n12344 45.487742 0.652281 0.432024 0.203684 1.743192 -2.439781 11.073802\n12345 45.493633 0.551670 0.372157 0.140293 1.956283 -2.365716 11.189658\n12346 45.499621 0.495708 0.338191 0.111472 2.001962 -2.281033 11.168575\n12347 45.505649 0.389423 0.278637 0.067746 1.822905 -2.101543 11.248502\n12348 45.511720 0.342669 0.251596 0.049688 1.741345 -2.083472 11.228540\n12349 45.517819 0.259700 0.203742 0.018856 1.609947 -2.082950 11.055700\n12350 45.523936 0.223730 0.183745 0.010288 1.518083 -2.036810 10.972945\n12351 45.529759 0.141731 0.150293 0.005604 1.368240 -1.890917 10.743279\n12352 45.535747 0.105386 0.136193 0.009143 1.256048 -1.794772 10.558557\n12353 45.541954 0.066245 0.115576 0.031825 0.997282 -1.576924 10.327636\n12354 45.548061 0.064478 0.105402 0.045356 0.858949 -1.409306 10.289599\n12355 45.554092 0.083076 0.082082 0.069464 0.455816 -0.930457 10.225692\n12356 45.560050 0.114006 0.067319 0.079690 0.308703 -0.864911 10.138075\n12357 45.566087 0.174890 0.025181 0.095478 0.204409 -0.944235 10.127277\n12358 45.571998 0.200768 -0.002460 0.103492 0.154526 -0.860580 10.034191\n12359 45.578261 0.266230 -0.049203 0.122624 0.134095 -0.748160 9.722119\n12360 45.584170 0.298861 -0.065400 0.132074 0.150876 -0.859847 9.630936\n12361 45.590406 0.357171 -0.083497 0.145497 0.220781 -1.170858 9.463418\n12362 45.596301 0.385336 -0.083497 0.146268 0.295457 -1.239068 9.466278\n12363 45.602295 0.424090 -0.071439 0.135127 0.504915 -1.184522 9.597939\n12364 45.608922 0.421022 -0.046680 0.123162 0.634816 -1.148648 9.274817\n12365 45.614421 0.408644 -0.025764 0.117277 0.679474 -1.174389 9.115826\n12366 45.620544 0.391884 -0.001263 0.111297 0.703589 -1.223577 9.010453\n12367 45.626415 0.351294 0.053833 0.101683 0.850671 -1.267289 9.089827\n12368 45.632858 0.342995 0.079669 0.096620 0.973296 -1.315134 9.335421\n12369 45.638604 0.304285 0.107045 0.086187 1.123674 -1.373455 10.419271\n12370 45.645066 0.271530 0.104562 0.081121 1.140191 -1.217398 10.823405\n12371 45.650824 0.186428 0.085062 0.071140 1.062369 -0.748422 11.343439\n12372 45.657224 0.049265 0.054367 0.065379 0.742717 -0.217178 11.603381\n12373 45.662745 -0.007421 0.049950 0.058785 0.524218 -0.110636 11.391952\n12374 45.669189 -0.065010 0.060105 0.028838 0.185933 -0.211751 10.769403\n12375 45.674948 -0.074797 0.073430 0.009413 0.151473 -0.306417 10.364329\n12376 45.681190 -0.038051 0.118118 -0.028325 0.280538 -0.310466 9.597192\n12377 45.686968 0.011288 0.147859 -0.043794 0.383783 -0.230162 9.250576\n12378 45.693358 0.130929 0.212866 -0.066924 0.572033 -0.210582 8.914655\n12379 45.699113 0.193204 0.238295 -0.075933 0.681345 -0.309999 8.837551\n12380 45.705226 0.333502 0.272638 -0.091695 1.011734 -0.609487 9.154957\n12381 45.711168 0.403167 0.276388 -0.097335 1.157981 -0.850022 9.421229\n12382 45.717232 0.476503 0.257681 -0.098362 1.451206 -1.061279 9.703025\n12383 45.723315 0.488011 0.243129 -0.091537 1.663640 -1.034153 9.756309\n12384 45.729383 0.431079 0.209057 -0.057750 2.094346 -1.001543 10.085244\n12385 45.735309 0.369447 0.188557 -0.035778 2.210812 -0.982255 10.196778\n12386 45.741271 0.222034 0.150707 -0.005105 1.970551 -1.146051 10.644251\n12387 45.747239 0.153798 0.126336 0.002409 1.185952 -1.353828 10.984581\n12388 45.753346 0.034322 0.087267 0.003433 0.119941 -0.928880 10.701766\n12389 45.759477 -0.007228 0.067025 -0.000419 0.182615 -0.540496 10.641953\n12390 45.765483 -0.125852 0.027398 0.019025 -0.015645 -0.031950 10.306131\n12391 45.771417 -0.157890 0.022765 0.028363 -0.041241 0.245489 10.124475\n12392 45.777482 -0.180057 0.040791 0.008695 -0.363294 0.883172 10.212233\n12393 45.783510 -0.183185 0.061449 -0.002561 -0.634964 1.154404 10.165860\n12394 45.789717 -0.158297 0.126171 -0.024452 -0.488667 1.439241 9.767505\n12395 45.795716 -0.135072 0.162298 -0.035228 -0.317029 1.442594 9.754190\n12396 45.801684 -0.104684 0.229781 -0.021098 0.000890 0.949450 9.784851\n12397 45.807701 -0.100970 0.262423 -0.002555 0.322377 0.542606 9.849925\n12398 45.813669 -0.107203 0.305963 0.038921 0.771112 -0.083551 10.124020\n12399 45.819803 -0.112538 0.311055 0.068241 0.913159 -0.335433 10.252340\n12400 45.825804 -0.106731 0.291356 0.121013 1.190408 -0.880015 10.536171\n12401 45.831843 -0.090678 0.266752 0.139868 1.091902 -1.035547 10.665319\n12402 45.837940 -0.030911 0.202597 0.179303 0.612849 -1.111177 10.670791\n12403 45.843881 0.010916 0.172062 0.195218 0.414669 -1.099619 10.558391\n12404 45.850122 0.101636 0.123257 0.217465 0.031626 -0.975096 10.149931\n12405 45.856007 0.150153 0.107149 0.227394 -0.013567 -0.923409 9.927432\n12406 45.862109 0.252330 0.097667 0.225420 0.205166 -0.888353 9.886151\n12407 45.867907 0.303925 0.102629 0.213171 0.260592 -0.813713 10.033955\n12408 45.874103 0.396766 0.132633 0.182752 0.343324 -0.628968 10.032253\n12409 45.880224 0.428766 0.156266 0.166547 0.411776 -0.548363 9.922138\n12410 45.886229 0.439981 0.212012 0.143021 0.459213 -0.564055 9.661522\n12411 45.892313 0.424414 0.242884 0.135732 0.532439 -0.700355 9.579906\n12412 45.898283 0.384295 0.296999 0.116332 0.709790 -0.933128 9.680456\n12413 45.904430 0.370620 0.315952 0.106273 0.717934 -0.961035 9.719264\n12414 45.910490 0.356800 0.340158 0.095143 0.733052 -0.845956 9.533664\n12415 45.916508 0.352579 0.345052 0.093673 0.724234 -0.714165 9.406923\n12416 45.922475 0.332523 0.336996 0.104830 0.568812 -0.543539 9.400522\n12417 45.928613 0.308079 0.320907 0.114528 0.468158 -0.491361 9.677930\n12418 45.934508 0.261403 0.265387 0.126661 0.186653 -0.635476 10.471499\n12419 45.940584 0.229470 0.226589 0.127553 -0.015007 -0.849465 10.822743\n12420 45.946619 0.160613 0.130929 0.119012 -0.502162 -1.164567 10.884284\n12421 45.952626 0.128231 0.081112 0.111509 -0.655526 -1.141515 10.704204\n12422 45.958849 0.075285 -0.013861 0.104506 -0.573150 -0.896162 10.215563\n12423 45.964713 0.058097 -0.056043 0.105616 -0.378877 -0.747872 10.046110\n12424 45.970782 0.052097 -0.132708 0.104366 0.014547 -0.522382 9.954198\n12425 45.976743 0.062365 -0.165654 0.099852 0.166842 -0.468022 10.011091\n12426 45.982911 0.085614 -0.217910 0.086415 0.428557 -0.270419 10.319079\n12427 45.989133 0.098410 -0.230643 0.081939 0.505116 -0.070959 10.453215\n12428 45.995021 0.115295 -0.220185 0.087529 0.600964 0.195610 10.524105\n12429 46.001005 0.117717 -0.198681 0.095845 0.638501 0.178165 10.411682\n12430 46.007095 0.119158 -0.123647 0.110196 0.552804 -0.010683 10.153848\n12431 46.013020 0.121498 -0.074212 0.112941 0.439484 -0.102184 10.095611\n12432 46.019091 0.136289 0.038166 0.103631 0.260738 -0.035177 10.130572\n12433 46.025322 0.156734 0.098808 0.093314 0.192101 0.022319 10.140878\n12434 46.031267 0.197742 0.216851 0.076451 0.020239 0.131109 9.939504\n12435 46.037181 0.216485 0.270959 0.071705 -0.081355 0.184968 9.708076\n12436 46.043379 0.251131 0.366813 0.067403 -0.233105 0.184083 9.393394\n12437 46.049362 0.280108 0.415971 0.065482 -0.308380 0.155041 9.316494\n12438 46.055507 0.336053 0.472928 0.055804 -0.449676 0.118121 9.149499\n12439 46.062097 0.416049 0.525309 0.033260 -0.641187 0.371986 8.979947\n12440 46.067467 0.460622 0.553341 0.021198 -0.675601 0.516450 8.693400\n12441 46.073997 0.502970 0.585015 0.010244 -0.661214 0.598944 8.359670\n12442 46.079523 0.600663 0.636143 -0.008276 -0.473577 0.709547 8.624333\n12443 46.085982 0.689472 0.632028 -0.017929 -0.213687 0.721672 9.685956\n12444 46.091806 0.827363 0.508182 -0.022805 0.034587 0.741790 12.198640\n12445 46.098078 0.861688 0.367972 -0.013144 0.028013 0.799771 12.753369\n12446 46.103734 0.787664 -0.014445 0.027844 -0.188230 0.945187 12.372581\n12447 46.110234 0.578400 -0.359820 0.082768 -0.940327 0.703131 12.179627\n12448 46.115882 0.448962 -0.466395 0.099396 -1.253945 0.580365 12.075503\n12449 46.122462 0.249571 -0.514792 0.089047 -1.148260 0.467305 11.006847\n12450 46.127837 0.195685 -0.472243 0.069913 -0.680753 0.369240 10.562478\n12451 46.134363 0.102749 -0.306611 0.015271 0.756952 0.147332 9.802876\n12452 46.139962 0.051631 -0.196642 -0.013681 1.320470 0.271396 9.512034\n12453 46.146343 -0.120052 0.051392 -0.058398 1.772084 0.478623 9.255564\n12454 46.152085 -0.181166 0.122172 -0.067836 1.593550 0.390737 9.282953\n12455 46.158392 -0.294211 0.252787 -0.084528 0.585414 0.082574 10.114620\n12456 46.163984 -0.298148 0.272261 -0.086696 0.093681 -0.039660 10.636054\n12457 46.170273 -0.192298 0.218730 -0.076147 -0.565562 -0.000328 11.117728\n12458 46.176005 -0.103114 0.157733 -0.059994 -0.782548 0.108406 11.205486\n12459 46.182382 0.056115 0.004682 -0.009011 -0.936867 0.222333 11.107888\n12460 46.188354 0.080048 -0.035783 0.004380 -0.913828 0.264050 10.948764\n12461 46.194284 0.080221 -0.099707 0.018126 -0.579512 0.159447 10.428995\n12462 46.200267 0.061967 -0.110380 0.013012 -0.205494 -0.002599 10.222028\n12463 46.206432 0.041118 -0.096800 -0.008499 0.550792 -0.051571 9.934457\n12464 46.212431 0.045745 -0.074914 -0.015929 0.744577 0.165534 9.786667\n12465 46.218455 0.060667 -0.002686 -0.020993 0.664871 0.542058 9.465528\n12466 46.224483 0.056222 0.046271 -0.022601 0.499601 0.588798 9.351411\n12467 46.230583 0.004035 0.154359 -0.029121 0.103058 0.531554 9.312401\n12468 46.236451 -0.023420 0.180294 -0.030231 0.022829 0.512876 9.460758\n12469 46.242664 -0.039366 0.160166 -0.015281 -0.072548 0.644042 10.103573\n12470 46.248525 -0.017281 0.120087 0.002344 -0.153604 0.703424 10.402959\n12471 46.254893 0.050613 0.018110 0.036259 -0.371970 0.516042 10.486522\n12472 46.260470 0.073224 -0.027280 0.042851 -0.460388 0.369905 10.297289\n12473 46.266724 0.062188 -0.081404 0.026876 -0.346366 0.112360 9.961339\n12474 46.272715 0.030317 -0.090123 0.007564 -0.198214 0.084975 9.917271\n12475 46.278925 -0.041615 -0.087117 -0.032941 0.040369 0.197875 9.975579\n12476 46.284792 -0.062834 -0.081691 -0.047641 0.117105 0.211386 10.009410\n12477 46.290949 -0.062622 -0.066947 -0.056676 0.099133 0.126574 10.013116\n12478 46.296807 -0.050021 -0.055805 -0.049886 0.031623 0.107309 9.937426\n12479 46.303017 -0.030611 -0.023056 -0.021837 -0.121268 0.232183 9.811129\n12480 46.308922 -0.029622 -0.005362 -0.005824 -0.172507 0.326002 9.852058\n12481 46.314945 -0.036150 0.016926 0.017191 -0.149533 0.298499 10.161978\n12482 46.321086 -0.034739 0.016012 0.020660 -0.066410 0.191912 10.373006\n12483 46.327134 -0.008583 -0.009368 0.012885 0.124704 0.036767 10.557695\n12484 46.333102 0.011648 -0.026591 0.005715 0.189719 0.043002 10.534275\n12485 46.338961 0.040216 -0.047695 -0.008703 0.199374 0.144474 10.394889\n12486 46.345121 0.039821 -0.045292 -0.016097 0.150225 0.237587 10.296646\n12487 46.351176 0.013659 -0.017879 -0.033836 0.029253 0.335136 10.176799\n12488 46.357303 -0.003747 -0.000426 -0.043278 0.012533 0.304209 10.176995\n12489 46.363339 -0.020100 0.023900 -0.051293 0.107997 0.232953 10.180084\n12490 46.369367 -0.014784 0.027848 -0.044703 0.164924 0.270067 10.134842\n12491 46.375474 0.012734 0.028378 -0.009465 0.124371 0.419330 9.967938\n12492 46.381497 0.026559 0.030763 0.012109 0.022450 0.428957 9.881702\n12493 46.387726 0.034404 0.044286 0.037356 -0.187481 0.265096 9.826327\n12494 46.393598 0.028187 0.050989 0.035483 -0.222310 0.176022 9.875733\n12495 46.399602 0.011967 0.049553 0.009324 -0.117663 0.096385 10.084181\n12496 46.405721 0.007723 0.038496 -0.006668 -0.034396 0.085970 10.170066\n12497 46.411753 0.008826 0.002633 -0.027220 -0.003602 0.175487 10.196404\n12498 46.417726 0.010702 -0.014545 -0.030273 -0.065779 0.228251 10.151984\n12499 46.423847 0.005751 -0.033851 -0.028281 -0.211018 0.266717 10.074364\n12500 46.429846 -0.003049 -0.035235 -0.026448 -0.229640 0.255553 10.044326\n12501 46.435695 -0.025355 -0.031059 -0.022224 -0.094341 0.302091 10.037172\n12502 46.441849 -0.032682 -0.029757 -0.018668 0.009093 0.356541 10.068624\n12503 46.447814 -0.031120 -0.028612 -0.007005 0.161207 0.385575 10.077511\n12504 46.454175 -0.023411 -0.026222 0.000240 0.179680 0.337280 10.030416\n12505 46.459889 -0.007327 -0.012932 0.011110 0.124373 0.249664 9.922428\n12506 46.465854 -0.003411 -0.002631 0.011948 0.097731 0.239407 9.920918\n12507 46.471923 -0.003573 0.016039 0.003127 0.074043 0.239941 10.053468\n12508 46.478061 -0.004810 0.020277 -0.005329 0.064120 0.229665 10.148648\n12509 46.484160 -0.002139 0.014546 -0.022590 0.022074 0.221361 10.285635\n12510 46.489988 0.003356 0.007226 -0.028056 -0.010182 0.228619 10.308581\n12511 46.496319 0.017205 -0.005300 -0.027429 -0.103813 0.205305 10.235667\n12512 46.502154 0.020851 -0.008255 -0.021968 -0.129129 0.187634 10.167800\n12513 46.508278 0.016664 -0.006711 -0.008868 -0.123671 0.198536 10.085623\n12514 46.514226 0.010308 -0.003701 -0.004167 -0.090815 0.205655 10.093488\n12515 46.520465 -0.003806 0.001875 -0.002154 0.002177 0.178178 10.133444\n12516 46.526329 -0.007917 0.003060 -0.004211 0.036547 0.180924 10.125436\n12517 46.532485 -0.009458 0.002901 -0.008701 0.040210 0.273674 10.059555\n12518 46.539100 -0.008105 0.003667 -0.009449 0.016516 0.311518 10.005755\n12519 46.544595 -0.005365 0.009031 -0.008932 -0.055809 0.302375 9.958383\n12520 46.551100 -0.005372 0.011546 -0.009201 -0.078847 0.284616 9.979115\n12521 46.556562 -0.005877 0.008378 -0.012197 -0.051945 0.277601 10.073691\n12522 46.563143 -0.002049 -0.006258 -0.015563 0.021584 0.295202 10.143164\n12523 46.568687 0.001504 -0.014636 -0.015654 0.044339 0.303921 10.135511\n12524 46.575264 0.006944 -0.024119 -0.011995 0.017317 0.337189 10.087927\n12525 46.580780 0.006835 -0.023085 -0.009865 -0.012109 0.333834 10.064488\n12526 46.587346 -0.000267 -0.012631 -0.007573 -0.028511 0.278447 10.048130\n12527 46.592960 -0.005864 -0.006541 -0.007872 -0.004488 0.243800 10.063673\n12528 46.599300 -0.015439 -0.000225 -0.010867 0.045743 0.222233 10.119477\n12529 46.604920 -0.017338 -0.000019 -0.011965 0.053262 0.226293 10.142364\n12530 46.611216 -0.013361 -0.003571 -0.010493 -0.006485 0.217380 10.144361\n12531 46.616922 -0.010111 -0.004486 -0.008412 -0.053494 0.218777 10.126985\n12532 46.623400 -0.004036 -0.002709 -0.004356 -0.114370 0.239032 10.118125\n12533 46.628976 -0.001539 -0.001198 -0.003916 -0.108133 0.232668 10.129189\n12534 46.635377 0.002078 -0.000454 -0.007160 -0.033363 0.207271 10.153438\n12535 46.641079 0.003419 -0.001705 -0.009652 0.011623 0.212229 10.161604\n12536 46.649375 0.005538 -0.005207 -0.013866 0.060450 0.227150 10.137094\n12537 46.653391 0.006131 -0.005245 -0.014888 0.062512 0.230668 10.120152\n12538 46.659324 0.005674 -0.000118 -0.013642 0.030161 0.257851 10.075477\n12539 46.665454 0.003972 0.003908 -0.011919 0.014765 0.281641 10.057177\n12540 46.671435 -0.001125 0.010985 -0.009149 0.005885 0.302696 10.056970\n12541 46.677289 -0.002813 0.012218 -0.008862 0.014630 0.299492 10.079380\n12542 46.683553 -0.003094 0.009926 -0.008789 0.027556 0.297519 10.103557\n12543 46.689411 -0.001818 0.007359 -0.008502 0.020699 0.304364 10.086928\n12544 46.695590 0.001650 0.002919 -0.006662 -0.005780 0.302111 10.052851\n12545 46.701470 0.002737 0.001809 -0.005870 -0.025277 0.287166 10.046820\n12546 46.707643 0.002657 0.001078 -0.006452 -0.047846 0.249253 10.046602\n12547 46.713595 0.002130 0.000043 -0.008293 -0.043878 0.249680 10.046578\n12548 46.719777 0.000563 -0.003571 -0.013296 -0.034048 0.249548 10.084852\n12549 46.725838 -0.000581 -0.005867 -0.015293 -0.034267 0.245035 10.099992\n12550 46.731587 -0.003213 -0.010427 -0.015791 -0.052425 0.246075 10.099483\n12551 46.737652 -0.004714 -0.011343 -0.014506 -0.064825 0.248283 10.097443\n12552 46.743796 -0.008547 -0.010389 -0.010030 -0.069801 0.247316 10.094365\n12553 46.749826 -0.010492 -0.010012 -0.007777 -0.058334 0.239879 10.090078\n12554 46.755918 -0.012472 -0.010238 -0.005913 -0.003921 0.244392 10.109583\n12555 46.761912 -0.012558 -0.011036 -0.006294 0.021254 0.258677 10.131006\n12556 46.767918 -0.010619 -0.012878 -0.008834 0.038376 0.264500 10.142405\n12557 46.774028 -0.009487 -0.012809 -0.009946 0.040092 0.266839 10.134740\n12558 46.780091 -0.007598 -0.009470 -0.011303 0.036968 0.276680 10.095836\n12559 46.786288 -0.006160 -0.006757 -0.011559 0.033994 0.279312 10.091537\n12560 46.792344 -0.002366 -0.000579 -0.012318 0.037513 0.268912 10.114394\n12561 46.798150 -0.000352 0.001555 -0.012600 0.047497 0.262932 10.117642\n12562 46.804226 0.002774 0.003314 -0.012482 0.052318 0.255134 10.117251\n12563 46.810353 0.003881 0.003851 -0.011698 0.044544 0.250665 10.113985\n12564 46.816435 0.005293 0.005251 -0.009052 0.002450 0.229880 10.089847\n12565 46.822396 0.005148 0.006693 -0.007669 -0.022832 0.228844 10.085624\n12566 46.828442 0.004093 0.008768 -0.006049 -0.044801 0.227718 10.086867\n12567 46.834430 0.003310 0.009253 -0.006317 -0.041188 0.222227 10.082892\n12568 46.840600 0.001468 0.007988 -0.008469 -0.040379 0.220185 10.088284\n12569 46.846599 0.000180 0.005790 -0.009976 -0.034468 0.227331 10.085350\n12570 46.852492 -0.002093 0.000036 -0.011557 -0.043956 0.248143 10.075264\n12571 46.858603 -0.002506 -0.002442 -0.011639 -0.047815 0.254897 10.064759\n12572 46.864603 -0.003511 -0.005018 -0.010565 -0.038403 0.269625 10.066603\n12573 46.870740 -0.003677 -0.005783 -0.010008 -0.032259 0.280910 10.070339\n12574 46.876850 -0.003839 -0.007284 -0.009715 -0.004789 0.288827 10.074856\n12575 46.882767 -0.003563 -0.007987 -0.010055 0.008913 0.273660 10.074450\n12576 46.888848 -0.004946 -0.008608 -0.011102 0.022949 0.253020 10.079857\n12577 46.894843 -0.006222 -0.008705 -0.011322 0.016592 0.266871 10.077127\n12578 46.900811 -0.007062 -0.008099 -0.011199 -0.001933 0.282343 10.084785\n12579 46.906941 -0.006837 -0.007334 -0.010946 0.001936 0.274216 10.088849\n12580 46.912968 -0.005832 -0.005258 -0.010491 0.017363 0.268978 10.094227\n12581 46.918992 -0.004927 -0.004731 -0.010667 0.018549 0.278955 10.098948\n12582 46.925104 -0.003379 -0.004454 -0.011428 0.005872 0.262930 10.103216\n12583 46.931049 -0.002848 -0.004692 -0.011612 -0.002102 0.246748 10.106807\n12584 46.937365 -0.002676 -0.004633 -0.011352 -0.023341 0.226283 10.117768\n12585 46.943144 -0.002972 -0.004381 -0.010868 -0.030703 0.221883 10.124369\n12586 46.949193 -0.002229 -0.003473 -0.010181 -0.021647 0.216007 10.141094\n12587 46.955107 -0.001874 -0.003053 -0.010291 -0.015492 0.219057 10.134377\n12588 46.961294 -0.002159 -0.002655 -0.010557 -0.012807 0.253948 10.131089\n12589 46.967229 -0.002087 -0.002673 -0.010626 -0.010042 0.271422 10.130868\n12590 46.973257 -0.002540 -0.002068 -0.010781 0.003885 0.240849 10.116417\n12591 46.979347 -0.003080 -0.001477 -0.010499 0.001856 0.230437 10.102637\n12592 46.985520 -0.003867 -0.000340 -0.009825 0.005199 0.276143 10.103946\n12593 46.991438 -0.003998 -0.000502 -0.009694 0.008784 0.290391 10.119168\n12594 46.997537 -0.002826 -0.001632 -0.009996 0.019124 0.278822 10.115464\n12595 47.003534 -0.001848 -0.002162 -0.010309 0.022344 0.278672 10.094613\n12596 47.009672 -0.001009 -0.002372 -0.010516 0.015489 0.306820 10.074380\n12597 47.015635 -0.001106 -0.002334 -0.010541 0.010422 0.300338 10.085507\n12598 47.021644 -0.001530 -0.001525 -0.010354 -0.016498 0.263424 10.094580\n12599 47.027970 -0.001826 -0.000733 -0.009725 -0.023181 0.267867 10.093172\n12600 47.033625 -0.001911 -0.000054 -0.009193 -0.027306 0.280718 10.095812\n12601 47.040024 -0.002141 0.000105 -0.009677 -0.024588 0.279512 10.092632\n12602 47.046022 -0.002566 -0.000914 -0.010440 -0.026854 0.251097 10.087494\n12603 47.052290 -0.003182 -0.003109 -0.011027 -0.034676 0.255445 10.090777\n12604 47.058022 -0.003487 -0.004032 -0.010692 -0.041036 0.255064 10.084985\n12605 47.064327 -0.004174 -0.004687 -0.010065 -0.044966 0.236666 10.074330\n12606 47.069881 -0.004612 -0.004976 -0.010290 -0.044526 0.244168 10.079659\n12607 47.076190 -0.004712 -0.005991 -0.010275 -0.022777 0.270578 10.096848\n12608 47.082091 -0.004454 -0.006358 -0.010337 -0.007509 0.268990 10.104897\n12609 47.088519 -0.004722 -0.007142 -0.010666 0.007737 0.258071 10.104834\n12610 47.094041 -0.005112 -0.007107 -0.010893 0.011625 0.257808 10.094438\n12611 47.100313 -0.005135 -0.005876 -0.011008 0.013797 0.265646 10.103245\n12612 47.106260 -0.004861 -0.005121 -0.010964 0.013462 0.260955 10.102841\n12613 47.112246 -0.004171 -0.003501 -0.010470 0.030366 0.255369 10.088057\n12614 47.118347 -0.003427 -0.002696 -0.010314 0.029202 0.263232 10.076920\n12615 47.124302 -0.001711 -0.001820 -0.010478 0.018023 0.279910 10.091017\n12616 47.130303 -0.001599 -0.001337 -0.010559 0.017654 0.272652 10.098820\n12617 47.136382 -0.001728 -0.000791 -0.010850 0.013117 0.253999 10.085668\n12618 47.142495 -0.001659 -0.000606 -0.010611 0.009715 0.259974 10.085463\n12619 47.148533 -0.001525 -0.000664 -0.010326 -0.000939 0.283955 10.105639\n12620 47.154603 -0.001456 -0.000905 -0.010442 -0.001641 0.277131 10.108376\n12621 47.160547 -0.001693 -0.000990 -0.010249 -0.005231 0.244843 10.102536\n12622 47.166489 -0.001795 -0.000947 -0.010383 -0.008286 0.255194 10.100312\n12623 47.172563 -0.002405 -0.000840 -0.010633 -0.005902 0.267069 10.079963\n12624 47.178702 -0.002953 -0.001000 -0.010551 -0.009070 0.244408 10.080778\n12625 47.184784 -0.004081 -0.002546 -0.010402 -0.013326 0.241147 10.073619\n12626 47.190699 -0.004354 -0.003454 -0.010316 -0.009011 0.262617 10.067461\n12627 47.196634 -0.003937 -0.004627 -0.010072 0.005391 0.262948 10.087375\n12628 47.202904 -0.003784 -0.004824 -0.009976 0.003747 0.259701 10.094464\n12629 47.208879 -0.004290 -0.004697 -0.010444 -0.004221 0.279627 10.092989\n12630 47.214818 -0.004495 -0.004573 -0.010732 -0.000500 0.285310 10.108502\n12631 47.220906 -0.004316 -0.003935 -0.010379 0.010730 0.261236 10.109695\n12632 47.227040 -0.004301 -0.003585 -0.009968 0.002301 0.252521 10.102036\n12633 47.232856 -0.003412 -0.002543 -0.009454 -0.007813 0.272047 10.081534\n12634 47.238997 -0.002953 -0.002308 -0.009435 -0.004083 0.284517 10.087277\n12635 47.244991 -0.001666 -0.001842 -0.009773 0.002634 0.274992 10.100947\n12636 47.251239 -0.001309 -0.001782 -0.010164 0.003072 0.271609 10.092172\n12637 47.257257 -0.001512 -0.001099 -0.010604 -0.015520 0.275195 10.100050\n12638 47.263209 -0.001375 -0.000679 -0.010663 -0.025335 0.274394 10.103739\n12639 47.269455 -0.001027 -0.000111 -0.010402 -0.018461 0.249900 10.098636\n12640 47.275331 -0.001247 -0.000141 -0.010233 -0.020222 0.252201 10.092272\n12641 47.281375 -0.002073 -0.000666 -0.010393 -0.013636 0.274755 10.087328\n12642 47.287296 -0.002256 -0.001312 -0.010146 -0.007912 0.274903 10.093351\n12643 47.293473 -0.002580 -0.002482 -0.009904 -0.018530 0.270523 10.093556\n12644 47.299496 -0.002910 -0.002997 -0.009807 -0.026335 0.269522 10.093015\n12645 47.305441 -0.003563 -0.003569 -0.010042 -0.018562 0.264655 10.124578\n12646 47.311516 -0.003524 -0.003447 -0.010204 -0.004384 0.262751 10.130114\n12647 47.317686 -0.003759 -0.003104 -0.010744 0.008465 0.250601 10.111615\n12648 47.323676 -0.004162 -0.003333 -0.010726 0.014414 0.256998 10.102522\n12649 47.329477 -0.004002 -0.003828 -0.009861 0.014250 0.294203 10.108105\n12650 47.335631 -0.003623 -0.003361 -0.009566 0.009740 0.290296 10.104041\n12651 47.341586 -0.003371 -0.002170 -0.009949 -0.002698 0.277849 10.076398\n12652 47.347678 -0.003156 -0.001785 -0.010180 -0.008168 0.283142 10.072396\n12653 47.353818 -0.002917 -0.001575 -0.010152 -0.015443 0.290013 10.085662\n12654 47.359834 -0.002971 -0.001467 -0.009942 -0.013136 0.286327 10.096876\n12655 47.365799 -0.003050 -0.001302 -0.009765 -0.013003 0.275207 10.102333\n12656 47.371894 -0.003137 -0.001368 -0.009648 -0.019769 0.274168 10.095425\n12657 47.377998 -0.002251 -0.002033 -0.009375 -0.029390 0.274246 10.107233\n12658 47.384049 -0.002288 -0.002259 -0.009465 -0.028460 0.259269 10.117886\n12659 47.390117 -0.002989 -0.002868 -0.010116 -0.030750 0.251336 10.108945\n12660 47.395923 -0.003217 -0.002663 -0.010414 -0.027365 0.267048 10.113891\n12661 47.402012 -0.003528 -0.001757 -0.010116 -0.015136 0.266917 10.150621\n12662 47.407938 -0.003623 -0.001677 -0.009820 -0.007556 0.251020 10.143067\n12663 47.414151 -0.003585 -0.002389 -0.009630 -0.000915 0.256501 10.103543\n12664 47.420625 -0.003642 -0.002911 -0.009775 0.000265 0.276728 10.095933\n12665 47.426349 -0.003039 -0.003344 -0.009510 -0.005143 0.289629 10.092914\n12666 47.432765 -0.002813 -0.003301 -0.009488 -0.004949 0.284653 10.096035\n12667 47.438358 -0.002447 -0.003001 -0.009929 -0.001034 0.288288 10.090293\n12668 47.444830 -0.002457 -0.001719 -0.010910 0.007947 0.282892 10.092036\n12669 47.450737 -0.002849 -0.001777 -0.010941 0.009535 0.272716 10.093246\n12670 47.456847 -0.003666 -0.002731 -0.010296 -0.001954 0.281908 10.074134\n12671 47.462394 -0.003500 -0.002557 -0.010294 -0.003720 0.293820 10.071958\n12672 47.468920 -0.003050 -0.002109 -0.010374 0.003218 0.276406 10.107509\n12673 47.474475 -0.002940 -0.002496 -0.009980 0.001217 0.265358 10.120895\n12674 47.480986 -0.003215 -0.002427 -0.009545 -0.012235 0.271652 10.122716\n12675 47.486798 -0.003357 -0.002368 -0.009502 -0.015038 0.272631 10.113689\n12676 47.493036 -0.003705 -0.002013 -0.010111 -0.024224 0.248872 10.088437\n12677 47.498802 -0.003897 -0.002286 -0.010404 -0.026348 0.240960 10.089529\n12678 47.504834 -0.003489 -0.002960 -0.010571 -0.021370 0.260663 10.095882\n12679 47.510919 -0.003376 -0.003268 -0.010594 -0.019382 0.280028 10.098153\n12680 47.517189 -0.003634 -0.004114 -0.010668 -0.018469 0.280217 10.093567\n12681 47.522933 -0.003616 -0.004126 -0.010353 -0.014413 0.279072 10.085081\n12682 47.529156 -0.004032 -0.003641 -0.010135 -0.019244 0.286855 10.077810\n12683 47.534877 -0.003917 -0.003479 -0.009916 -0.013834 0.278690 10.081200\n12684 47.541262 -0.003663 -0.003384 -0.009598 -0.003311 0.245421 10.069793\n12685 47.546926 -0.003739 -0.003622 -0.009599 0.003006 0.247683 10.064511\n12686 47.553275 -0.003572 -0.003418 -0.009984 0.021347 0.275403 10.074187\n12687 47.559064 -0.003805 -0.003040 -0.010207 0.028104 0.279925 10.083447\n12688 47.565262 -0.003888 -0.002735 -0.010461 0.017447 0.270778 10.101275\n12689 47.571215 -0.003718 -0.002844 -0.010282 0.009549 0.278003 10.105073\n12690 47.577305 -0.003140 -0.002569 -0.010332 0.001115 0.289336 10.104091\n12691 47.583327 -0.002960 -0.001996 -0.010461 -0.003994 0.273998 10.099133\n12692 47.589388 -0.002876 -0.001058 -0.010842 0.000929 0.266293 10.087885\n12693 47.595329 -0.002721 -0.000885 -0.010934 -0.004244 0.278493 10.093622\n12694 47.601361 -0.002852 -0.001763 -0.009995 -0.012915 0.271368 10.101429\n12695 47.607466 -0.003215 -0.002119 -0.009835 -0.011873 0.260582 10.096508\n12696 47.613452 -0.003533 -0.003056 -0.009582 -0.006247 0.254933 10.081938\n12697 47.619451 -0.003705 -0.003685 -0.009887 -0.009268 0.266133 10.079915\n12698 47.625497 -0.003967 -0.003933 -0.010700 -0.006532 0.270136 10.088323\n12699 47.631698 -0.004257 -0.003549 -0.011012 -0.004944 0.259722 10.096627\n12700 47.637748 -0.005182 -0.003858 -0.011002 -0.016072 0.278042 10.099227\n12701 47.643687 -0.005590 -0.004165 -0.010820 -0.016591 0.286758 10.098998\n12702 47.650333 -0.004828 -0.003955 -0.010610 -0.006113 0.269899 10.091271\n12703 47.655674 -0.004594 -0.003961 -0.010340 -0.000699 0.264965 10.087411\n12704 47.661788 -0.004041 -0.004203 -0.009459 0.006724 0.287164 10.099184\n12705 47.667667 -0.003582 -0.004070 -0.009512 0.004876 0.297546 10.108157\n12706 47.673718 -0.002891 -0.003363 -0.010225 0.002223 0.272280 10.096558\n12707 47.679742 -0.002754 -0.002879 -0.010433 0.006574 0.258131 10.082407\n12708 47.685872 -0.002657 -0.002778 -0.010973 0.002104 0.271533 10.087545\n12709 47.691858 -0.002526 -0.002592 -0.011094 0.008153 0.287615 10.099353\n12710 47.697950 -0.002820 -0.002590 -0.010326 0.007174 0.280498 10.104221\n12711 47.703928 -0.002925 -0.002938 -0.010050 -0.001293 0.277843 10.099132\n12712 47.709991 -0.002954 -0.003022 -0.010506 -0.013240 0.289226 10.115712\n12713 47.716191 -0.002793 -0.002707 -0.010716 -0.012262 0.292149 10.117638\n12714 47.722190 -0.002982 -0.001864 -0.010417 0.006243 0.264223 10.107457\n12715 47.728172 -0.003271 -0.001847 -0.010354 0.011657 0.260099 10.102609\n12716 47.734149 -0.003796 -0.002873 -0.009886 -0.004334 0.269347 10.091938\n12717 47.740105 -0.003542 -0.003234 -0.009739 -0.021526 0.265620 10.084549\n12718 47.746281 -0.003417 -0.003476 -0.009748 -0.022975 0.229511 10.069035\n12719 47.752424 -0.003292 -0.003472 -0.009858 -0.015073 0.236630 10.068754\n12720 47.758295 -0.002770 -0.003324 -0.010398 -0.014708 0.294493 10.091528\n12721 47.764554 -0.002810 -0.002800 -0.010571 -0.016147 0.307104 10.100683\n12722 47.770411 -0.003722 -0.001930 -0.010683 -0.002829 0.303761 10.099575\n12723 47.776415 -0.004076 -0.001986 -0.010877 0.005524 0.298611 10.091442\n12724 47.782461 -0.003417 -0.002238 -0.010789 0.012396 0.278642 10.083564\n12725 47.788397 -0.003173 -0.002181 -0.010668 0.013607 0.272577 10.079876\n12726 47.794490 -0.003435 -0.002398 -0.010145 0.002675 0.269383 10.090765\n12727 47.800584 -0.003776 -0.002419 -0.009688 -0.004091 0.278953 10.101392\n12728 47.806605 -0.003618 -0.001895 -0.010099 -0.010867 0.277687 10.097615\n12729 47.812784 -0.003294 -0.001504 -0.010454 -0.004763 0.263890 10.089983\n12730 47.818610 -0.003472 -0.001887 -0.011768 0.008991 0.250152 10.085347\n12731 47.824738 -0.003601 -0.002255 -0.011819 0.015284 0.258387 10.094639\n12732 47.830814 -0.003580 -0.002732 -0.010839 0.012474 0.278960 10.110789\n12733 47.836775 -0.003719 -0.002805 -0.010355 0.005657 0.281416 10.099151\n12734 47.842916 -0.003935 -0.003004 -0.009642 -0.012684 0.281876 10.094445\n12735 47.849510 -0.003968 -0.002806 -0.009551 -0.023126 0.286716 10.098038\n12736 47.854877 -0.003469 -0.002028 -0.009866 -0.031454 0.284590 10.098760\n12737 47.860913 -0.003417 -0.002200 -0.009913 -0.028295 0.278472 10.102887\n12738 47.866953 -0.004088 -0.003272 -0.010477 -0.003415 0.280283 10.111703\n12739 47.873583 -0.004317 -0.003335 -0.010359 -0.003946 0.285615 10.111145\n12740 47.878992 -0.004125 -0.003451 -0.009774 -0.003989 0.275104 10.101766\n12741 47.885656 -0.004680 -0.003463 -0.009425 0.019140 0.277966 10.102721\n12742 47.891312 -0.004549 -0.003256 -0.009677 0.019046 0.286437 10.095984\n12743 47.897719 -0.003582 -0.002703 -0.010076 0.007475 0.283664 10.091649\n12744 47.903227 -0.003260 -0.002173 -0.010035 0.002488 0.274668 10.087789\n12745 47.909802 -0.003467 -0.001644 -0.009764 -0.011741 0.284414 10.071092\n12746 47.915243 -0.003372 -0.001646 -0.009701 -0.016623 0.290305 10.065325\n12747 47.921816 -0.003343 -0.002201 -0.009636 -0.002225 0.276618 10.098589\n12748 47.927314 -0.003537 -0.002324 -0.009228 0.010328 0.268483 10.117017\n12749 47.934032 -0.003632 -0.002747 -0.009607 0.003718 0.291684 10.121981\n12750 47.939394 -0.003519 -0.002337 -0.009777 -0.009475 0.301914 10.125288\n12751 47.945868 -0.003173 -0.001479 -0.009985 -0.012623 0.291723 10.114890\n12752 47.951568 -0.003266 -0.001386 -0.010257 -0.005214 0.279281 10.106806\n12753 47.957942 -0.003788 -0.002836 -0.010823 -0.002503 0.287185 10.103640\n12754 47.963639 -0.003930 -0.003328 -0.010795 -0.004431 0.287868 10.097216\n12755 47.969904 -0.003536 -0.003630 -0.010251 -0.003316 0.268844 10.078152\n12756 47.975688 -0.003301 -0.003567 -0.009910 -0.007594 0.266350 10.076337\n12757 47.982064 -0.003129 -0.003088 -0.009774 -0.005525 0.272442 10.093582\n12758 47.987656 -0.002836 -0.002308 -0.009884 -0.003289 0.267022 10.103205\n12759 47.994035 -0.003090 -0.001238 -0.010784 0.011873 0.252731 10.097628\n12760 47.999988 -0.003394 -0.001079 -0.010861 0.015989 0.256759 10.089027\n12761 48.005995 -0.003464 -0.001939 -0.010369 0.004991 0.270527 10.091277\n12762 48.011960 -0.003120 -0.002291 -0.010188 0.007204 0.268376 10.106519\n12763 48.018121 -0.002856 -0.002855 -0.010073 0.015757 0.261515 10.107295\n12764 48.024075 -0.002697 -0.002733 -0.010223 0.007515 0.273693 10.103995\n12765 48.030068 -0.003021 -0.002644 -0.010355 -0.016515 0.299985 10.122185\n12766 48.036017 -0.003386 -0.002363 -0.010519 -0.014760 0.295941 10.126826\n12767 48.042116 -0.003918 -0.001937 -0.010662 -0.000666 0.277118 10.110807\n12768 48.048301 -0.004107 -0.002049 -0.010649 0.000561 0.273770 10.114817\n12769 48.054330 -0.004086 -0.002515 -0.010272 -0.010854 0.260611 10.116444\n12770 48.060224 -0.003912 -0.002562 -0.010087 -0.008541 0.248261 10.107771\n12771 48.066275 -0.004006 -0.003092 -0.009848 0.009422 0.264580 10.087081\n12772 48.072301 -0.004096 -0.003456 -0.009744 0.008908 0.289058 10.090129\n12773 48.078415 -0.003620 -0.003136 -0.009782 -0.003246 0.309706 10.102800\n12774 48.084450 -0.003342 -0.002707 -0.010093 -0.010332 0.298415 10.096346\n12775 48.090338 -0.003672 -0.002279 -0.010976 -0.005452 0.286331 10.074703\n12776 48.096493 -0.004126 -0.002393 -0.011341 0.002719 0.293105 10.076585\n12777 48.102363 -0.002916 -0.002393 -0.011130 0.008026 0.293835 10.107394\n12778 48.108564 -0.002610 -0.002369 -0.010540 0.006421 0.282067 10.112343\n12779 48.114876 -0.003091 -0.002382 -0.009264 0.005104 0.274189 10.113918\n12780 48.120612 -0.002909 -0.002351 -0.009115 0.002667 0.281884 10.111966\n12781 48.126749 -0.002642 -0.002182 -0.009360 -0.006044 0.288304 10.110712\n12782 48.132736 -0.002807 -0.002206 -0.009482 -0.004923 0.275808 10.105991\n12783 48.138855 -0.003852 -0.002553 -0.009822 -0.000983 0.274132 10.118583\n12784 48.144768 -0.004151 -0.002961 -0.009661 0.001243 0.282170 10.128202\n12785 48.150806 -0.003200 -0.003373 -0.009017 -0.005885 0.262997 10.110085\n12786 48.156756 -0.003222 -0.003123 -0.009152 -0.005718 0.254687 10.093070\n12787 48.162864 -0.003809 -0.002988 -0.010030 0.001256 0.276936 10.105996\n12788 48.168961 -0.003638 -0.002842 -0.010122 0.006480 0.276942 10.123079\n12789 48.175058 -0.003531 -0.002456 -0.010603 0.000793 0.256656 10.111698\n12790 48.180860 -0.003715 -0.002520 -0.010545 0.009208 0.261868 10.094043\n12791 48.187044 -0.003687 -0.002345 -0.010653 0.026958 0.284753 10.073787\n12792 48.193014 -0.003430 -0.002660 -0.010570 0.027061 0.274347 10.081996\n12793 48.199038 -0.003026 -0.003932 -0.009894 0.006635 0.251867 10.098817\n12794 48.205310 -0.003240 -0.004010 -0.009665 -0.000916 0.261338 10.103140\n12795 48.211038 -0.003557 -0.003537 -0.009776 -0.008835 0.301992 10.109539\n12796 48.217316 -0.003381 -0.003243 -0.009793 -0.014821 0.301646 10.104975\n12797 48.223185 -0.003676 -0.002656 -0.010542 -0.011095 0.280971 10.081801\n12798 48.229252 -0.003955 -0.002368 -0.011215 -0.003180 0.275236 10.086992\n12799 48.235372 -0.004874 -0.002171 -0.011090 -0.002884 0.281342 10.109202\n12800 48.241280 -0.004608 -0.002541 -0.010480 -0.005414 0.279063 10.110697\n12801 48.247804 -0.004065 -0.003511 -0.009385 -0.008588 0.280283 10.111385\n12802 48.253446 -0.003862 -0.003852 -0.009317 -0.012181 0.291989 10.105533\n12803 48.259464 -0.003157 -0.003578 -0.009670 -0.008587 0.291434 10.097185\n12804 48.265586 -0.003350 -0.003018 -0.010306 -0.004983 0.277926 10.080979\n12805 48.271869 -0.003845 -0.001854 -0.011167 -0.005621 0.277598 10.082326\n12806 48.277589 -0.003759 -0.001899 -0.010999 -0.002334 0.285821 10.085387\n12807 48.283710 -0.003540 -0.002472 -0.010204 0.010057 0.271608 10.094643\n12808 48.289609 -0.003588 -0.003052 -0.009588 0.007646 0.261655 10.091097\n12809 48.295822 -0.003485 -0.004000 -0.009234 -0.004163 0.270729 10.084936\n12810 48.301834 -0.003233 -0.004170 -0.009328 -0.006115 0.284413 10.091110\n12811 48.307815 -0.002934 -0.003377 -0.009613 0.001055 0.284782 10.094415\n12812 48.314265 -0.003409 -0.002047 -0.010473 -0.012221 0.275605 10.095037\n12813 48.319875 -0.003802 -0.001869 -0.010827 -0.007104 0.286047 10.093111\n12814 48.326415 -0.004192 -0.001551 -0.010838 -0.002343 0.300242 10.094762\n12815 48.331889 -0.004193 -0.001795 -0.010731 -0.000943 0.283457 10.087379\n12816 48.338373 -0.003394 -0.003082 -0.010186 0.012801 0.265371 10.082641\n12817 48.344127 -0.002999 -0.003059 -0.009601 0.011484 0.276769 10.086665\n12818 48.350450 -0.002063 -0.001706 -0.009464 0.000903 0.279635 10.111415\n12819 48.356334 -0.001813 -0.001068 -0.010241 -0.006432 0.274165 10.108761\n12820 48.362416 -0.002748 -0.001514 -0.011133 -0.018525 0.285381 10.102568\n12821 48.368269 -0.003812 -0.002542 -0.010974 -0.011657 0.294851 10.112112\n12822 48.374460 -0.003884 -0.003713 -0.010436 -0.001642 0.278187 10.106322\n12823 48.380417 -0.003934 -0.004065 -0.010112 -0.001540 0.270721 10.100795\n12824 48.386644 -0.004624 -0.004615 -0.009367 -0.009922 0.292190 10.107792\n12825 48.392582 -0.004654 -0.004438 -0.009525 -0.015554 0.298330 10.107786\n12826 48.398572 -0.004301 -0.003241 -0.010195 -0.004137 0.274711 10.091153\n12827 48.404481 -0.004372 -0.002524 -0.010854 -0.002281 0.271227 10.095553\n12828 48.410521 -0.004388 -0.001810 -0.011580 -0.007545 0.291729 10.118911\n12829 48.416624 -0.004633 -0.002055 -0.011382 -0.001146 0.283898 10.123346\n12830 48.422481 -0.004610 -0.002241 -0.010345 0.011735 0.258085 10.111225\n12831 48.428486 -0.004327 -0.002147 -0.009920 0.013961 0.259847 10.105794\n12832 48.434642 -0.003911 -0.002283 -0.009860 -0.001623 0.285135 10.089214\n12833 48.440708 -0.003603 -0.001948 -0.009892 -0.020512 0.283301 10.084484\n12834 48.446921 -0.003674 -0.001367 -0.009826 -0.025676 0.271861 10.086659\n12835 48.452674 -0.003940 -0.001319 -0.010082 -0.020963 0.268462 10.091958\n12836 48.458846 -0.003500 -0.001267 -0.010490 -0.004954 0.278224 10.100004\n12837 48.464791 -0.002966 -0.001264 -0.010390 0.002397 0.278765 10.108857\n12838 48.470700 -0.002908 -0.001712 -0.009763 0.011772 0.281335 10.108336\n12839 48.476796 -0.003175 -0.002434 -0.009429 0.009589 0.282841 10.104773\n12840 48.482862 -0.003760 -0.002881 -0.009175 -0.012944 0.280017 10.100111\n12841 48.489049 -0.003611 -0.002690 -0.009592 -0.020382 0.275040 10.106030\n12842 48.494962 -0.003345 -0.002034 -0.010259 -0.019749 0.266682 10.116179\n12843 48.500957 -0.003430 -0.001556 -0.010227 -0.013071 0.273444 10.113562\n12844 48.507077 -0.003875 -0.001371 -0.010285 0.007982 0.270560 10.116210\n12845 48.513312 -0.004171 -0.002120 -0.010425 0.015016 0.255557 10.111056\n12846 48.519195 -0.004116 -0.003596 -0.010185 0.018690 0.244845 10.082069\n12847 48.525304 -0.003707 -0.003724 -0.009909 0.018116 0.249337 10.075725\n12848 48.531313 -0.002743 -0.003145 -0.009527 0.002688 0.265061 10.078303\n12849 48.537407 -0.002913 -0.002591 -0.009530 -0.005190 0.272676 10.074184\n12850 48.543330 -0.003259 -0.001980 -0.010236 -0.008645 0.290111 10.087389\n12851 48.549327 -0.003262 -0.001872 -0.010486 -0.006833 0.292144 10.111174\n12852 48.555526 -0.003464 -0.001710 -0.010693 0.001306 0.270582 10.111050\n12853 48.561354 -0.003562 -0.001671 -0.010332 0.005368 0.254654 10.097704\n12854 48.567680 -0.004110 -0.002364 -0.009449 0.010078 0.243206 10.085912\n12855 48.573437 -0.004299 -0.002842 -0.009084 0.008263 0.257056 10.081944\n12856 48.579619 -0.003613 -0.003044 -0.008905 0.008470 0.272907 10.099338\n12857 48.585560 -0.003385 -0.002802 -0.009303 0.006098 0.263386 10.099400\n12858 48.591602 -0.003150 -0.001049 -0.010594 0.000046 0.279161 10.109141\n12859 48.597619 -0.002941 -0.000605 -0.011335 0.001842 0.290919 10.113730\n12860 48.603648 -0.003024 -0.001013 -0.011247 0.011886 0.274441 10.100867\n12861 48.609775 -0.003296 -0.001823 -0.010389 0.008526 0.262505 10.093563\n12862 48.615705 -0.003694 -0.003039 -0.008641 -0.005603 0.276937 10.084971\n12863 48.621792 -0.003375 -0.003157 -0.008137 -0.005513 0.278900 10.085013\n12864 48.627904 -0.003384 -0.003190 -0.008799 0.005800 0.273482 10.088858\n12865 48.633956 -0.003535 -0.002737 -0.009305 0.009369 0.287629 10.091337\n12866 48.639907 -0.004137 -0.002726 -0.010422 0.010543 0.307591 10.097447\n12867 48.646157 -0.004375 -0.002460 -0.010751 0.011153 0.300330 10.101744\n12868 48.652036 -0.004667 -0.002490 -0.010157 0.015502 0.260228 10.078972\n12869 48.658105 -0.004674 -0.002913 -0.009444 0.019338 0.258841 10.066518\n12870 48.664114 -0.003775 -0.003621 -0.009471 0.017841 0.278586 10.078657\n12871 48.670100 -0.003286 -0.003519 -0.009615 0.012876 0.282451 10.086668\n12872 48.676141 -0.002866 -0.002408 -0.010049 0.000053 0.282299 10.081535\n12873 48.682245 -0.002720 -0.002418 -0.010255 -0.002731 0.285952 10.081147\n12874 48.688350 -0.003261 -0.001993 -0.010523 -0.014968 0.284398 10.102867\n12875 48.694240 -0.003281 -0.001870 -0.010592 -0.009713 0.269713 10.108332\n12876 48.700392 -0.003314 -0.001789 -0.010805 0.000974 0.254116 10.091969\n12877 48.706337 -0.003369 -0.002261 -0.010594 -0.002159 0.266283 10.089108\n12878 48.712518 -0.004131 -0.003569 -0.010344 -0.017965 0.281184 10.084792\n12879 48.719047 -0.004714 -0.003904 -0.010361 -0.030643 0.272399 10.084188\n12880 48.724575 -0.004706 -0.003672 -0.010403 -0.026150 0.281245 10.093544\n12881 48.731044 -0.004417 -0.002453 -0.011021 0.000522 0.304702 10.102577\n12882 48.736533 -0.004157 -0.001961 -0.011046 0.011408 0.310609 10.102292\n12883 48.743000 -0.003943 -0.001867 -0.010241 0.007624 0.300793 10.104429\n12884 48.748831 -0.003839 -0.002407 -0.009612 0.000859 0.296496 10.109337\n12885 48.755186 -0.003489 -0.003508 -0.009442 -0.005868 0.288827 10.101726\n12886 48.760791 -0.003338 -0.003363 -0.009511 -0.003092 0.286355 10.091989\n12887 48.767046 -0.003376 -0.002164 -0.010493 0.003154 0.288125 10.079123\n12888 48.772794 -0.003347 -0.001633 -0.010766 0.005257 0.294919 10.087716\n12889 48.779344 -0.003413 -0.001802 -0.010923 -0.001279 0.304110 10.093894\n12890 48.784853 -0.003534 -0.001892 -0.010803 -0.002036 0.295199 10.094642\n12891 48.791154 -0.003780 -0.002446 -0.010287 0.007500 0.282103 10.096790\n12892 48.796893 -0.003691 -0.003085 -0.009790 0.005506 0.282363 10.097753\n12893 48.803246 -0.003843 -0.003003 -0.009429 0.008196 0.265444 10.116529\n12894 48.809273 -0.004088 -0.002697 -0.009587 0.008778 0.261567 10.123929\n12895 48.815130 -0.004381 -0.002338 -0.010118 -0.006402 0.278366 10.114169\n12896 48.821285 -0.004241 -0.002042 -0.010662 -0.019008 0.276464 10.102519\n12897 48.827325 -0.003765 -0.001660 -0.010831 -0.026466 0.260740 10.088196\n12898 48.833280 -0.003970 -0.001634 -0.010614 -0.019861 0.260523 10.082951\n12899 48.839413 -0.004002 -0.001822 -0.009689 0.006424 0.285897 10.090028\n12900 48.845244 -0.003672 -0.001907 -0.009340 0.012673 0.298185 10.103233\n12901 48.851427 -0.003079 -0.001700 -0.009358 0.013581 0.294583 10.106470\n12902 48.857557 -0.003179 -0.001539 -0.009763 0.005625 0.287149 10.101809\n12903 48.863619 -0.003401 -0.001343 -0.010899 0.004347 0.285576 10.086228\n12904 48.869514 -0.003089 -0.001171 -0.010968 0.011240 0.282311 10.084456\n12905 48.875595 -0.003739 -0.000582 -0.010715 0.030934 0.270309 10.083807\n12906 48.881543 -0.004046 -0.001018 -0.010341 0.027728 0.273309 10.086091\n12907 48.887715 -0.004096 -0.002537 -0.009395 -0.002375 0.295027 10.095565\n12908 48.893694 -0.004010 -0.003153 -0.009652 -0.007570 0.287707 10.100790\n12909 48.899852 -0.003744 -0.002951 -0.010386 -0.010434 0.276289 10.087841\n12910 48.905821 -0.004062 -0.002598 -0.010564 -0.012202 0.283729 10.081586\n12911 48.911865 -0.003890 -0.001925 -0.011138 -0.012752 0.281233 10.085190\n12912 48.917908 -0.003488 -0.001371 -0.011319 -0.009873 0.270145 10.076355\n12913 48.923807 -0.003623 -0.001265 -0.010552 -0.010235 0.262011 10.062996\n12914 48.930049 -0.003755 -0.002060 -0.009989 -0.014408 0.270437 10.075619\n12915 48.935894 -0.002979 -0.003173 -0.009442 0.001650 0.265294 10.107459\n12916 48.942104 -0.002711 -0.003396 -0.009500 0.004084 0.263664 10.107776\n12917 48.948142 -0.003532 -0.002530 -0.010051 -0.005521 0.275351 10.113950\n12918 48.953927 -0.004292 -0.001874 -0.010701 -0.012919 0.289341 10.120708\n12919 48.960201 -0.004845 -0.001545 -0.010719 -0.007063 0.284020 10.108210\n12920 48.966169 -0.004669 -0.001583 -0.010644 -0.002535 0.259326 10.094212\n12921 48.972188 -0.004580 -0.002625 -0.010493 0.011113 0.253746 10.082664\n12922 48.978248 -0.004673 -0.003529 -0.010151 0.019047 0.272248 10.074255\n12923 48.984306 -0.003884 -0.004332 -0.009294 0.021881 0.280093 10.065092\n12924 48.990365 -0.003495 -0.004070 -0.009409 0.015008 0.276245 10.080606\n12925 48.996402 -0.003265 -0.002413 -0.010041 -0.000376 0.295057 10.093575\n12926 49.002395 -0.003159 -0.001398 -0.010332 0.000600 0.297337 10.100863\n12927 49.008393 -0.003248 -0.000757 -0.011361 0.010614 0.271670 10.100964\n12928 49.014350 -0.003466 -0.000899 -0.011522 0.012689 0.265779 10.094520\n12929 49.020522 -0.003950 -0.001623 -0.010497 0.008855 0.288667 10.108894\n12930 49.026527 -0.003937 -0.002405 -0.010006 0.006974 0.288959 10.113651\n12931 49.032605 -0.003168 -0.003188 -0.009313 -0.002240 0.269811 10.101030\n12932 49.038737 -0.003193 -0.002933 -0.009083 -0.005892 0.276380 10.086468\n12933 49.044785 -0.003393 -0.002303 -0.009776 -0.002252 0.309108 10.091968\n12934 49.050815 -0.003320 -0.002243 -0.010025 0.002627 0.310791 10.103286\n12935 49.056671 -0.003704 -0.002238 -0.010444 0.017809 0.275356 10.128473\n12936 49.062792 -0.003707 -0.002566 -0.010531 0.015618 0.263995 10.134266\n12937 49.068835 -0.003531 -0.002859 -0.010479 -0.004027 0.277468 10.129330\n12938 49.074924 -0.003736 -0.002359 -0.010522 -0.006216 0.277134 10.123059\n12939 49.081081 -0.003819 -0.002232 -0.010069 0.002875 0.273220 10.119441\n12940 49.086975 -0.004419 -0.002666 -0.009869 0.004645 0.281326 10.116050\n12941 49.093072 -0.004978 -0.002679 -0.010450 -0.001012 0.291736 10.108183\n12942 49.099607 -0.004769 -0.002539 -0.010841 -0.004291 0.281655 10.109600\n12943 49.105141 -0.004693 -0.002520 -0.011353 0.001629 0.267629 10.096750\n12944 49.111816 -0.004098 -0.002681 -0.010640 0.021483 0.288049 10.099710\n12945 49.117257 -0.003667 -0.002885 -0.009948 0.018301 0.285960 10.100932\n12946 49.123788 -0.002509 -0.003131 -0.009274 -0.005984 0.271439 10.096453\n12947 49.129277 -0.002450 -0.003158 -0.009317 -0.022521 0.279959 10.102338\n12948 49.135763 -0.003358 -0.002463 -0.010101 -0.042004 0.298917 10.117743\n12949 49.141403 -0.003940 -0.001910 -0.010497 -0.034231 0.302174 10.125031\n12950 49.148005 -0.004412 -0.001977 -0.010622 -0.007434 0.272949 10.117604\n12951 49.153420 -0.004069 -0.002567 -0.010237 -0.004395 0.265725 10.102178\n12952 49.159842 -0.003670 -0.003754 -0.009650 0.000303 0.264033 10.095266\n12953 49.165297 -0.003686 -0.003900 -0.009453 0.009204 0.256466 10.090187\n12954 49.171958 -0.003404 -0.002914 -0.009804 0.012313 0.256141 10.096648\n12955 49.177642 -0.003294 -0.002268 -0.010172 0.009437 0.273876 10.098472\n12956 49.183835 -0.002793 -0.002199 -0.010685 0.009802 0.308842 10.101418\n12957 49.189692 -0.003036 -0.002087 -0.010805 0.010920 0.300319 10.100531\n12958 49.195986 -0.004146 -0.001835 -0.011142 0.021474 0.270884 10.085772\n12959 49.201842 -0.004559 -0.002107 -0.010803 0.017061 0.258164 10.086297\n12960 49.207914 -0.003539 -0.003274 -0.009765 0.003698 0.266316 10.099897\n12961 49.213775 -0.003113 -0.003599 -0.009355 0.003230 0.266634 10.106133\n12962 49.219924 -0.002825 -0.003561 -0.009361 0.020703 0.277396 10.094678\n12963 49.225862 -0.002820 -0.003540 -0.009574 0.025324 0.300461 10.100648\n12964 49.232101 -0.002797 -0.003270 -0.010498 0.028637 0.309713 10.122313\n12965 49.237873 -0.003149 -0.002858 -0.010752 0.028369 0.289677 10.121197\n12966 49.244244 -0.003573 -0.002398 -0.010836 0.024849 0.266043 10.099655\n12967 49.250012 -0.003874 -0.002717 -0.010669 0.018400 0.282262 10.100991\n12968 49.256212 -0.003541 -0.003047 -0.009882 0.005061 0.288067 10.125552\n12969 49.262194 -0.003471 -0.002789 -0.009638 0.003228 0.285594 10.120503\n12970 49.268273 -0.003215 -0.002407 -0.009589 -0.006064 0.308037 10.108148\n12971 49.274193 -0.003080 -0.002483 -0.009810 -0.005411 0.319656 10.111485\n12972 49.280325 -0.003702 -0.002298 -0.010357 -0.008512 0.295460 10.107759\n12973 49.286178 -0.004082 -0.002200 -0.010279 -0.006151 0.282442 10.097943\n12974 49.292435 -0.004294 -0.002175 -0.010181 0.000980 0.286753 10.107692\n12975 49.298299 -0.004275 -0.002469 -0.010353 0.003917 0.282098 10.109412\n12976 49.304428 -0.003753 -0.002601 -0.009914 0.003805 0.266149 10.100978\n12977 49.310605 -0.003740 -0.002509 -0.009775 -0.007789 0.270917 10.097855\n12978 49.316448 -0.004386 -0.002531 -0.009922 -0.014741 0.295775 10.123346\n12979 49.322595 -0.004302 -0.002451 -0.010225 -0.007274 0.294683 10.130173\n12980 49.328711 -0.004479 -0.001977 -0.010892 0.015595 0.266757 10.112279\n12981 49.334569 -0.004597 -0.002031 -0.010967 0.021370 0.264611 10.100912\n12982 49.340682 -0.004262 -0.003398 -0.010184 0.035516 0.289130 10.090519\n12983 49.346532 -0.003891 -0.003462 -0.009809 0.027996 0.284241 10.095928\n12984 49.352767 -0.003446 -0.002825 -0.010355 0.006490 0.263227 10.095147\n12985 49.358772 -0.003765 -0.002908 -0.010513 -0.002463 0.279669 10.095754\n12986 49.364758 -0.003633 -0.002566 -0.010742 0.000128 0.312079 10.111399\n12987 49.370726 -0.003530 -0.002362 -0.010872 0.000442 0.303470 10.116507\n12988 49.376785 -0.004366 -0.002076 -0.011064 -0.001670 0.289964 10.090390\n12989 49.382849 -0.004698 -0.001933 -0.011224 -0.000995 0.298030 10.093267\n12990 49.388867 -0.004328 -0.002196 -0.010285 0.003345 0.304728 10.120747\n12991 49.394821 -0.004125 -0.002493 -0.009992 0.002755 0.284626 10.125629\n12992 49.400877 -0.004555 -0.002752 -0.009635 0.002428 0.270900 10.110420\n12993 49.406988 -0.004429 -0.002996 -0.009869 -0.000232 0.284866 10.110128\n12994 49.413207 -0.003549 -0.002355 -0.010375 -0.012196 0.292146 10.112555\n12995 49.418951 -0.003815 -0.001966 -0.010656 -0.008909 0.277857 10.103633\n12996 49.425127 -0.004321 -0.001924 -0.010899 0.008533 0.281972 10.088758\n12997 49.431225 -0.004262 -0.002048 -0.010801 0.012560 0.293372 10.094841\n12998 49.437336 -0.004155 -0.002110 -0.010889 0.009627 0.282416 10.106992\n12999 49.443606 -0.004437 -0.001965 -0.010778 0.005037 0.270109 10.103573\n13000 49.449267 -0.004514 -0.001563 -0.010575 0.013404 0.281664 10.101096\n13001 49.455274 -0.004196 -0.001527 -0.010490 0.018392 0.292685 10.101573\n13002 49.461404 -0.003496 -0.001376 -0.010373 0.024618 0.273460 10.107773\n13003 49.467420 -0.003593 -0.001719 -0.010297 0.024680 0.263937 10.104829\n13004 49.473522 -0.003672 -0.002975 -0.010055 0.015512 0.291622 10.109795\n13005 49.479404 -0.003521 -0.003204 -0.009778 0.008882 0.298199 10.111889\n13006 49.485575 -0.003056 -0.002568 -0.009478 -0.001871 0.275413 10.111857\n13007 49.491639 -0.003105 -0.002466 -0.009683 0.000100 0.273819 10.099664\n13008 49.497709 -0.004056 -0.002253 -0.009742 0.001233 0.299819 10.096573\n13009 49.503726 -0.004199 -0.002508 -0.009879 -0.005341 0.298872 10.104778\n13010 49.509921 -0.004394 -0.002919 -0.009789 -0.004778 0.270691 10.114199\n13011 49.515809 -0.004041 -0.003105 -0.009546 -0.000076 0.265702 10.106991\n13012 49.521825 -0.003395 -0.003247 -0.009151 0.006729 0.275483 10.095288\n13013 49.528279 -0.003375 -0.002920 -0.009128 0.001751 0.279047 10.087343\n13014 49.533968 -0.004131 -0.002427 -0.009908 -0.002976 0.281619 10.083617\n13015 49.540351 -0.004165 -0.002770 -0.010512 -0.000706 0.315570 10.110887\n13016 49.546010 -0.003847 -0.002654 -0.010415 -0.002422 0.321322 10.123081\n13017 49.552495 -0.003634 -0.002671 -0.010623 -0.003527 0.284431 10.114882\n13018 49.558128 -0.003733 -0.003055 -0.010328 -0.001446 0.272995 10.105729\n13019 49.564606 -0.004411 -0.003527 -0.009433 0.002843 0.287716 10.090672\n13020 49.570098 -0.004649 -0.003283 -0.009353 0.005515 0.290330 10.089121\n13021 49.576539 -0.004620 -0.002886 -0.009486 0.002536 0.278551 10.094913\n13022 49.582269 -0.004789 -0.002610 -0.009833 -0.001111 0.279481 10.099369\n13023 49.588384 -0.004930 -0.001814 -0.010548 0.001514 0.296472 10.118872\n13024 49.594248 -0.004645 -0.001172 -0.011012 0.003878 0.289102 10.116996\n13025 49.600547 -0.004226 -0.001158 -0.011161 0.010845 0.275397 10.088913\n13026 49.606335 -0.004382 -0.001619 -0.010680 0.007351 0.279787 10.086387\n13027 49.612557 -0.004011 -0.002307 -0.009830 -0.002161 0.296868 10.102220\n13028 49.618399 -0.003483 -0.002687 -0.009216 -0.004403 0.289934 10.109727\n13029 49.624654 -0.003247 -0.003345 -0.008974 -0.002053 0.287722 10.112740\n13030 49.630524 -0.003525 -0.003461 -0.009135 0.000124 0.301607 10.115169\n13031 49.636460 -0.003769 -0.002800 -0.009803 0.003063 0.297548 10.124393\n13032 49.642531 -0.003914 -0.002603 -0.009872 0.004333 0.278816 10.117492\n13033 49.648624 -0.004927 -0.002946 -0.010266 0.004852 0.260054 10.099095\n13034 49.654715 -0.005130 -0.003240 -0.010461 0.000641 0.272761 10.106656\n13035 49.660715 -0.004819 -0.003453 -0.010142 -0.019033 0.289717 10.113160\n13036 49.666779 -0.004930 -0.003359 -0.010145 -0.018216 0.279761 10.104979\n13037 49.672739 -0.004295 -0.002581 -0.010353 -0.008383 0.273342 10.082160\n13038 49.678814 -0.003877 -0.002266 -0.010318 -0.001511 0.288533 10.078341\n13039 49.685069 -0.003714 -0.001910 -0.010304 0.009749 0.294942 10.106758\n13040 49.690940 -0.003788 -0.001710 -0.010424 0.018692 0.286952 10.104082\n13041 49.696910 -0.003956 -0.002342 -0.010588 0.024865 0.291686 10.078409\n13042 49.702847 -0.004065 -0.002684 -0.010447 0.022221 0.298291 10.075690\n13043 49.709232 -0.003777 -0.002725 -0.009833 0.016059 0.301842 10.076208\n13044 49.715196 -0.003773 -0.002467 -0.009943 0.015167 0.296572 10.073042\n13045 49.721162 -0.003437 -0.002225 -0.010734 0.000449 0.320078 10.096335\n13046 49.727173 -0.003477 -0.002093 -0.010903 -0.007080 0.337457 10.114375\n13047 49.733287 -0.003524 -0.002097 -0.010197 -0.001764 0.308623 10.127477\n13048 49.739123 -0.004193 -0.002297 -0.010126 0.004521 0.280106 10.114524\n13049 49.745246 -0.004650 -0.002881 -0.010201 0.007321 0.278169 10.105701\n13050 49.751254 -0.004399 -0.002968 -0.010045 0.007423 0.287563 10.109409\n13051 49.757342 -0.003671 -0.002401 -0.009651 -0.002809 0.286483 10.098144\n13052 49.763240 -0.003626 -0.002285 -0.009650 -0.009136 0.285109 10.088151\n13053 49.769448 -0.003871 -0.002800 -0.010116 -0.012251 0.308569 10.096757\n13054 49.775562 -0.003874 -0.002675 -0.010195 -0.009087 0.308698 10.099756\n13055 49.781358 -0.003636 -0.001684 -0.010605 0.004472 0.275316 10.100698\n13056 49.787576 -0.003669 -0.001422 -0.010431 0.013382 0.271091 10.099117\n13057 49.793596 -0.003837 -0.002512 -0.009815 0.015819 0.298650 10.113679\n13058 49.799713 -0.003515 -0.003148 -0.009971 0.012374 0.296477 10.118200\n13059 49.805624 -0.003572 -0.003585 -0.009809 -0.001583 0.281412 10.097573\n13060 49.811604 -0.003928 -0.003747 -0.009920 -0.016840 0.292476 10.097785\n13061 49.817575 -0.004647 -0.002852 -0.010537 -0.026618 0.313898 10.100451\n13062 49.823696 -0.004668 -0.002151 -0.010965 -0.021680 0.300784 10.102225\n13063 49.829741 -0.004787 -0.001831 -0.011135 -0.011456 0.268918 10.081869\n13064 49.835889 -0.004820 -0.002022 -0.010556 -0.006384 0.264992 10.080714\n13065 49.842092 -0.003542 -0.002805 -0.009943 -0.000267 0.275090 10.089159\n13066 49.847972 -0.002663 -0.003278 -0.009526 0.000112 0.270912 10.084885\n13067 49.853973 -0.002490 -0.002967 -0.009158 -0.004192 0.270844 10.075110\n13068 49.859959 -0.003230 -0.002923 -0.009501 -0.006680 0.286852 10.080960\n13069 49.866202 -0.003597 -0.002189 -0.009761 -0.010054 0.286949 10.089995\n13070 49.872065 -0.003324 -0.001524 -0.010188 -0.005336 0.274263 10.096740\n13071 49.878198 -0.004013 -0.001210 -0.010483 -0.003170 0.288572 10.097847\n13072 49.884194 -0.004231 -0.001441 -0.010153 -0.008687 0.301071 10.103025\n13073 49.890282 -0.003859 -0.002331 -0.009275 -0.009385 0.281675 10.102008\n13074 49.896321 -0.003717 -0.002654 -0.009323 -0.011114 0.269425 10.095286\n13075 49.902345 -0.003740 -0.002616 -0.009844 0.000518 0.292104 10.082076\n13076 49.908385 -0.003601 -0.002665 -0.009888 0.003911 0.317795 10.094022\n13077 49.914290 -0.003916 -0.002184 -0.010094 0.001684 0.308043 10.123816\n13078 49.920505 -0.004288 -0.001705 -0.010327 0.004116 0.284983 10.111567\n13079 49.926517 -0.004566 -0.001402 -0.010500 0.026402 0.270573 10.106724\n13080 49.932537 -0.004524 -0.001921 -0.010110 0.022503 0.274792 10.111423\n13081 49.938525 -0.003885 -0.003099 -0.009731 -0.001571 0.281783 10.103865\n13082 49.944555 -0.003577 -0.003241 -0.009703 -0.008497 0.279112 10.099846\n13083 49.950717 -0.003816 -0.002215 -0.009828 -0.023423 0.297354 10.103277\n13084 49.956678 -0.003675 -0.001729 -0.009951 -0.025713 0.301858 10.126804\n13085 49.962783 -0.003545 -0.001762 -0.009988 -0.018905 0.290865 10.123974\n13086 49.968655 -0.003611 -0.001692 -0.010227 -0.013943 0.287665 10.115149\n13087 49.975028 -0.003435 -0.002049 -0.010134 -0.008731 0.298917 10.103011\n13088 49.980813 -0.003488 -0.002232 -0.009920 -0.009469 0.290993 10.103483\n13089 49.986901 -0.003820 -0.002886 -0.009716 -0.004822 0.253988 10.114830\n13090 49.993393 -0.004205 -0.003074 -0.009774 -0.004104 0.254389 10.111113\n13091 49.999071 -0.004151 -0.003022 -0.009688 -0.003660 0.289995 10.098565\n13092 50.005537 -0.004189 -0.002536 -0.009871 0.012031 0.287476 10.118161\n13093 50.011021 -0.004166 -0.002570 -0.010446 0.020319 0.283376 10.110147\n13094 50.017694 -0.004150 -0.002835 -0.010679 0.013798 0.288249 10.094438\n13095 50.023263 -0.003760 -0.002683 -0.010341 0.008712 0.293943 10.092787\n13096 50.029694 -0.003109 -0.002527 -0.009905 0.004470 0.284504 10.076774\n13097 50.035181 -0.002928 -0.002869 -0.009761 0.007603 0.279991 10.071727\n13098 50.041536 -0.003289 -0.003080 -0.009936 0.000948 0.304647 10.087509\n13099 50.047807 -0.003637 -0.003042 -0.010187 -0.005148 0.310793 10.090653\n13100 50.053654 -0.004167 -0.002518 -0.010827 -0.002445 0.287906 10.106316\n13101 50.059287 -0.004553 -0.002301 -0.010991 0.001721 0.276035 10.114070\n13102 50.065557 -0.004842 -0.002289 -0.010481 0.005346 0.280255 10.103141\n13103 50.071349 -0.004552 -0.002469 -0.010005 0.006031 0.286022 10.102385\n13104 50.077774 -0.003648 -0.002906 -0.009536 0.014027 0.284955 10.082503\n13105 50.083429 -0.003494 -0.003192 -0.009491 0.011696 0.295370 10.074446\n13106 50.089815 -0.003337 -0.003538 -0.009949 0.008038 0.311069 10.087876\n13107 50.095650 -0.003550 -0.003145 -0.010045 0.001983 0.298845 10.100909\n13108 50.101577 -0.004145 -0.002458 -0.009920 -0.005971 0.268347 10.117910\n13109 50.107789 -0.004023 -0.002135 -0.009797 0.000789 0.267751 10.115996\n13110 50.113653 -0.003284 -0.001991 -0.009498 0.008695 0.280598 10.089705\n13111 50.119638 -0.003027 -0.002223 -0.009538 0.004629 0.281128 10.085440\n13112 50.125772 -0.003104 -0.002431 -0.009649 0.007001 0.281334 10.095883\n13113 50.131788 -0.003209 -0.002749 -0.009640 0.010826 0.301536 10.103611\n13114 50.137815 -0.003220 -0.002570 -0.009925 0.016982 0.296838 10.106910\n13115 50.143757 -0.003183 -0.002043 -0.010212 0.022650 0.286189 10.106190\n13116 50.149917 -0.003661 -0.002507 -0.010514 0.021038 0.304541 10.110365\n13117 50.155849 -0.003759 -0.002631 -0.010300 0.012661 0.315996 10.110454\n13118 50.161963 -0.003269 -0.002727 -0.010261 -0.002272 0.290142 10.104799\n13119 50.168018 -0.003428 -0.002919 -0.009993 -0.008544 0.270854 10.086200\n13120 50.174169 -0.004447 -0.003065 -0.009588 0.001635 0.264693 10.076694\n13121 50.180030 -0.004644 -0.003127 -0.009557 0.006327 0.280227 10.087893\n13122 50.185992 -0.004394 -0.002242 -0.010005 0.011005 0.279917 10.089983\n13123 50.192102 -0.004411 -0.002071 -0.010288 0.007484 0.280474 10.087300\n13124 50.198249 -0.004127 -0.002553 -0.010176 -0.001782 0.299591 10.094269\n13125 50.204231 -0.004025 -0.002817 -0.010004 0.010719 0.299713 10.110624\n13126 50.210210 -0.003449 -0.002904 -0.010393 0.031380 0.268583 10.127761\n13127 50.216334 -0.003387 -0.002593 -0.010191 0.027559 0.274423 10.115203\n13128 50.222284 -0.003426 -0.002648 -0.010332 -0.001809 0.322317 10.099682\n13129 50.228374 -0.003396 -0.002971 -0.010796 -0.006458 0.326785 10.094955\n13130 50.234319 -0.003778 -0.002929 -0.011204 -0.011621 0.291177 10.075321\n13131 50.240576 -0.003838 -0.003026 -0.010997 -0.013172 0.281049 10.056616\n13132 50.246309 -0.003673 -0.003297 -0.009973 -0.001334 0.296939 10.047311\n13133 50.252362 -0.003746 -0.003248 -0.009460 0.004882 0.291093 10.055894\n13134 50.258640 -0.003653 -0.003055 -0.009513 0.011071 0.263448 10.076171\n13135 50.264701 -0.003748 -0.002902 -0.009591 0.007694 0.272182 10.082745\n13136 50.270819 -0.003773 -0.002697 -0.010274 -0.003361 0.295096 10.093938\n13137 50.276636 -0.003459 -0.002635 -0.010371 -0.006527 0.290337 10.102814\n13138 50.282700 -0.003285 -0.002626 -0.010197 0.000446 0.286936 10.099406\n13139 50.288746 -0.003252 -0.002713 -0.010275 0.003638 0.295618 10.103580\n13140 50.294797 -0.003945 -0.003091 -0.010297 0.007474 0.312284 10.119357\n13141 50.300746 -0.004134 -0.002943 -0.010312 0.006432 0.291974 10.116146\n13142 50.306852 -0.004623 -0.003137 -0.010511 0.003313 0.262249 10.089138\n13143 50.312938 -0.004864 -0.002823 -0.010567 -0.002663 0.276478 10.086914\n13144 50.318910 -0.003732 -0.001745 -0.010467 -0.016621 0.300823 10.105246\n13145 50.324941 -0.003143 -0.001449 -0.010538 -0.010917 0.294745 10.100537\n13146 50.330915 -0.003637 -0.002354 -0.010616 -0.006129 0.303553 10.077971\n13147 50.337195 -0.003951 -0.002753 -0.010660 -0.003341 0.310532 10.078284\n13148 50.343073 -0.003666 -0.002616 -0.010259 0.004997 0.292605 10.104399\n13149 50.349262 -0.003573 -0.002305 -0.010236 0.004189 0.282563 10.102729\n13150 50.355136 -0.003280 -0.001938 -0.010252 -0.000598 0.308770 10.101780\n13151 50.361315 -0.003400 -0.002235 -0.010291 0.001165 0.319329 10.107074\n13152 50.367243 -0.004090 -0.002682 -0.010543 -0.001606 0.291731 10.105533\n13153 50.373319 -0.004397 -0.002543 -0.010662 -0.003537 0.272111 10.101255\n13154 50.379345 -0.004233 -0.002085 -0.010815 -0.012551 0.274230 10.106141\n13155 50.385275 -0.004142 -0.002178 -0.010711 -0.008044 0.275932 10.114954\n13156 50.391367 -0.004222 -0.002570 -0.009902 0.013072 0.262428 10.125300\n13157 50.397434 -0.004262 -0.002518 -0.009679 0.011625 0.268327 10.123606\n13158 50.403547 -0.004391 -0.002282 -0.010001 0.005112 0.299653 10.101107\n13159 50.409647 -0.003993 -0.002239 -0.010147 0.003138 0.298351 10.097133\n13160 50.415568 -0.003516 -0.001791 -0.010592 0.016965 0.272401 10.075487\n13161 50.421494 -0.003923 -0.001743 -0.010747 0.017086 0.276245 10.066023\n13162 50.427537 -0.003852 -0.001668 -0.010773 0.008569 0.297746 10.091323\n13163 50.433732 -0.004026 -0.002071 -0.010653 0.007505 0.297559 10.103503\n13164 50.439793 -0.003979 -0.002995 -0.010356 -0.000418 0.289341 10.102204\n13165 50.445691 -0.004123 -0.003480 -0.010431 -0.001117 0.295274 10.097230\n13166 50.451756 -0.004100 -0.003204 -0.010536 -0.002327 0.310209 10.108747\n13167 50.457782 -0.004080 -0.002781 -0.010260 -0.001830 0.304351 10.111679\n13168 50.463889 -0.004839 -0.001887 -0.009994 0.000870 0.275788 10.092738\n13169 50.470502 -0.004703 -0.001599 -0.009857 -0.008489 0.279182 10.105068\n13170 50.475930 -0.004446 -0.001578 -0.010270 -0.007646 0.279666 10.117747\n13171 50.481970 -0.004222 -0.001464 -0.010702 -0.004815 0.278417 10.114622\n13172 50.488108 -0.003908 -0.002044 -0.010176 -0.003871 0.274512 10.096253\n13173 50.494635 -0.003833 -0.002579 -0.009813 -0.006037 0.282398 10.098224\n13174 50.500318 -0.003718 -0.002511 -0.009477 -0.014209 0.303878 10.103848\n13175 50.506824 -0.003695 -0.002598 -0.009654 -0.001496 0.285339 10.086734\n13176 50.512397 -0.004034 -0.002578 -0.010074 0.007954 0.280066 10.082267\n13177 50.518651 -0.004053 -0.002410 -0.010184 0.006777 0.282998 10.089037\n13178 50.524266 -0.004028 -0.002325 -0.010119 0.001614 0.277507 10.087440\n13179 50.530896 -0.004421 -0.003040 -0.010424 -0.003549 0.290358 10.070136\n13180 50.536560 -0.004533 -0.003550 -0.010580 -0.005860 0.303871 10.066058\n13181 50.542819 -0.004212 -0.002685 -0.010919 0.005782 0.304312 10.085398\n13182 50.548430 -0.004073 -0.001812 -0.010844 0.011429 0.296801 10.098415\n13183 50.554804 -0.003966 -0.001044 -0.010642 0.012040 0.296885 10.110355\n13184 50.560583 -0.003867 -0.001695 -0.010564 0.015729 0.300439 10.109610\n13185 50.566785 -0.003307 -0.002861 -0.010344 0.016009 0.292030 10.109867\n13186 50.572651 -0.003265 -0.003041 -0.010166 0.019603 0.282390 10.095927\n13187 50.578805 -0.003502 -0.003176 -0.010141 0.017933 0.298567 10.082590\n13188 50.584653 -0.003595 -0.003287 -0.010095 0.010675 0.320146 10.092954\n13189 50.590907 -0.003707 -0.002723 -0.009709 -0.012717 0.305406 10.100896\n13190 50.596820 -0.003605 -0.002060 -0.009671 -0.013098 0.285019 10.098582\n13191 50.602911 -0.004413 -0.002076 -0.010001 -0.005524 0.280239 10.099184\n13192 50.608937 -0.004556 -0.002251 -0.010255 0.003231 0.286075 10.103126\n13193 50.614953 -0.004425 -0.003069 -0.010240 0.024873 0.272656 10.113395\n13194 50.621088 -0.004519 -0.003424 -0.009943 0.027388 0.271081 10.114636\n13195 50.627060 -0.004464 -0.003028 -0.009382 0.013329 0.296297 10.104568\n13196 50.633058 -0.004044 -0.002707 -0.009357 0.007455 0.297888 10.105010\n13197 50.639218 -0.003889 -0.002390 -0.009572 0.000020 0.289111 10.091900\n13198 50.645182 -0.004118 -0.002472 -0.010157 -0.001707 0.284921 10.080184\n13199 50.651294 -0.003943 -0.002404 -0.010440 0.000033 0.292599 10.088135\n13200 50.657238 -0.004147 -0.001993 -0.010135 0.003531 0.293253 10.104205\n13201 50.663337 -0.004780 -0.001749 -0.009878 0.008628 0.273209 10.118152\n13202 50.669248 -0.004659 -0.001976 -0.010110 0.009895 0.271969 10.122127\n13203 50.675195 -0.004337 -0.002469 -0.010078 0.013140 0.289309 10.128288\n13204 50.681334 -0.004149 -0.002884 -0.009691 0.013019 0.285951 10.123874\n13205 50.687424 -0.003966 -0.002777 -0.009699 -0.004355 0.280573 10.107142\n13206 50.693371 -0.003946 -0.002180 -0.009682 -0.008123 0.291762 10.101603\n13207 50.699577 -0.003586 -0.001637 -0.009843 0.005278 0.309399 10.088898\n13208 50.705621 -0.003227 -0.001720 -0.009791 0.011052 0.297951 10.081441\n13209 50.711581 -0.003812 -0.002210 -0.009598 0.017620 0.282437 10.091483\n13210 50.717597 -0.003981 -0.002476 -0.009549 0.011624 0.289307 10.103606\n13211 50.723580 -0.004029 -0.002818 -0.009528 -0.006769 0.296772 10.112736\n13212 50.729813 -0.004061 -0.003027 -0.009533 -0.010619 0.291271 10.106030\n13213 50.735544 -0.004003 -0.003011 -0.009637 -0.005523 0.296155 10.086721\n13214 50.741777 -0.003774 -0.002735 -0.010146 -0.004128 0.304913 10.079458\n13215 50.747808 -0.003565 -0.002179 -0.011131 0.004120 0.308183 10.100148\n13216 50.753886 -0.003671 -0.002188 -0.011083 0.002889 0.292831 10.107136\n13217 50.759808 -0.004598 -0.002401 -0.010592 0.003327 0.290958 10.114822\n13218 50.765973 -0.004940 -0.002478 -0.010529 -0.001556 0.297475 10.117443\n13219 50.772049 -0.003648 -0.002414 -0.010226 0.007775 0.286684 10.101478\n13220 50.778126 -0.003364 -0.002300 -0.010070 0.015841 0.275860 10.090580\n13221 50.784003 -0.004212 -0.002353 -0.010290 0.019832 0.290161 10.093281\n13222 50.789996 -0.004142 -0.002281 -0.010032 0.011261 0.306784 10.095512\n13223 50.796113 -0.003784 -0.002423 -0.010064 0.001343 0.304949 10.104828\n13224 50.802269 -0.004047 -0.002597 -0.010266 0.001460 0.297891 10.103771\n13225 50.808243 -0.004479 -0.003395 -0.010748 -0.006216 0.311673 10.105000\n13226 50.814210 -0.004128 -0.003553 -0.010727 -0.010552 0.309244 10.111905\n13227 50.820589 -0.003818 -0.003038 -0.010343 -0.015376 0.281968 10.113920\n13228 50.826464 -0.004168 -0.002870 -0.010350 -0.010455 0.282233 10.102558\n13229 50.832427 -0.004756 -0.003197 -0.010348 -0.005308 0.308995 10.108058\n13230 50.838366 -0.004376 -0.003328 -0.010216 -0.005798 0.307991 10.123608\n13231 50.844448 -0.003525 -0.002905 -0.009974 0.005372 0.277845 10.122265\n13232 50.850630 -0.003506 -0.002481 -0.010181 0.016692 0.272973 10.106109\n13233 50.856428 -0.003966 -0.002632 -0.010182 0.019399 0.300544 10.113811\n13234 50.862790 -0.004043 -0.002863 -0.009994 0.014559 0.303936 10.127059\n13235 50.868655 -0.003933 -0.002642 -0.010161 0.005575 0.294947 10.111177\n13236 50.874701 -0.003578 -0.002480 -0.010123 0.001001 0.302819 10.093791\n13237 50.880696 -0.003275 -0.002591 -0.010258 -0.005540 0.306428 10.087994\n13238 50.886754 -0.003458 -0.002539 -0.010464 -0.002407 0.287428 10.088013\n13239 50.892860 -0.003784 -0.001781 -0.010419 0.014904 0.269787 10.105852\n13240 50.898861 -0.003792 -0.001673 -0.010126 0.010183 0.284151 10.115992\n13241 50.905182 -0.003217 -0.002739 -0.009663 0.000704 0.297161 10.096395\n13242 50.910869 -0.003145 -0.002918 -0.009656 0.002855 0.285428 10.088887\n13243 50.917004 -0.004121 -0.002857 -0.009746 0.008352 0.289059 10.091105\n13244 50.923488 -0.004135 -0.002291 -0.009822 -0.000297 0.309907 10.103175\n13245 50.929152 -0.003902 -0.001862 -0.010154 -0.004593 0.305632 10.109327\n13246 50.935387 -0.004098 -0.002078 -0.010156 0.010149 0.280420 10.102180\n13247 50.941059 -0.004038 -0.002462 -0.010026 0.017994 0.279493 10.097836\n13248 50.947538 -0.003681 -0.002908 -0.009581 0.009139 0.289062 10.082320\n13249 50.953198 -0.003534 -0.002932 -0.009185 0.000853 0.286592 10.077626\n13250 50.959526 -0.003164 -0.002599 -0.009711 -0.005262 0.267617 10.076488\n13251 50.965247 -0.003550 -0.002647 -0.010156 -0.009046 0.282397 10.078674\n13252 50.971701 -0.004092 -0.002341 -0.010342 0.000981 0.302606 10.095737\n13253 50.977471 -0.003744 -0.001928 -0.010561 0.003513 0.289049 10.098408\n13254 50.983616 -0.003635 -0.001926 -0.010758 0.005838 0.285812 10.102308\n13255 50.989401 -0.003868 -0.001910 -0.010537 0.008239 0.304817 10.103086\n13256 50.995678 -0.003384 -0.002521 -0.009977 0.008224 0.303754 10.109091\n13257 51.001493 -0.003487 -0.002872 -0.009490 0.004666 0.292107 10.105723\n13258 51.007626 -0.004467 -0.003533 -0.009147 -0.004135 0.296365 10.101686\n13259 51.013591 -0.004435 -0.003557 -0.009848 -0.004554 0.311159 10.100213\n13260 51.019722 -0.003698 -0.002489 -0.010792 -0.006894 0.319343 10.095620\n13261 51.025715 -0.003434 -0.002108 -0.010820 -0.003686 0.308998 10.094728\n13262 51.031594 -0.003794 -0.001898 -0.010677 0.005954 0.298102 10.091770\n13263 51.037839 -0.003834 -0.001933 -0.010552 0.007653 0.292469 10.098849\n13264 51.043925 -0.003856 -0.002337 -0.010100 0.007620 0.272236 10.102414\n13265 51.049727 -0.003823 -0.002699 -0.010162 0.006248 0.265466 10.100259\n13266 51.055741 -0.004365 -0.002959 -0.009873 -0.005580 0.290424 10.096853\n13267 51.061877 -0.004405 -0.002782 -0.009621 -0.002666 0.302484 10.096543\n13268 51.067814 -0.004173 -0.001985 -0.010017 -0.000251 0.286027 10.092269\n13269 51.074009 -0.004365 -0.001682 -0.010081 0.004041 0.270467 10.092440\n13270 51.080011 -0.004289 -0.002204 -0.010356 0.002440 0.275670 10.101112\n13271 51.085983 -0.004174 -0.002606 -0.010462 0.004205 0.281203 10.104720\n13272 51.092056 -0.004228 -0.002625 -0.009918 0.000881 0.283994 10.101288\n13273 51.098121 -0.004707 -0.002464 -0.009520 -0.000628 0.289778 10.098122\n13274 51.104347 -0.004583 -0.002001 -0.009617 -0.009814 0.309326 10.097791\n13275 51.110240 -0.004056 -0.001814 -0.010024 -0.015908 0.301112 10.097567\n13276 51.116307 -0.004181 -0.001878 -0.010167 -0.012166 0.272590 10.098481\n13277 51.122337 -0.004836 -0.001979 -0.009808 -0.009224 0.271857 10.106276\n13278 51.128351 -0.004836 -0.002542 -0.009842 0.004803 0.290357 10.097903\n13279 51.134425 -0.004037 -0.003011 -0.009903 0.009664 0.281184 10.086102\n13280 51.140470 -0.003137 -0.003193 -0.010355 0.019605 0.274314 10.081957\n13281 51.146426 -0.003032 -0.003053 -0.010528 0.012667 0.291463 10.094880\n13282 51.152391 -0.003047 -0.002646 -0.010648 0.002496 0.314787 10.101600\n13283 51.158451 -0.003069 -0.002497 -0.010648 0.006280 0.296739 10.097996\n13284 51.164543 -0.003659 -0.002120 -0.010613 0.006668 0.278105 10.093226\n13285 51.170787 -0.004169 -0.002215 -0.010607 0.009254 0.293272 10.095379\n13286 51.176666 -0.004487 -0.002517 -0.010516 0.021984 0.301937 10.109915\n13287 51.182685 -0.004341 -0.002571 -0.010110 0.021195 0.287561 10.109980\n13288 51.188772 -0.004378 -0.002695 -0.010111 0.014383 0.282011 10.098089\n13289 51.194721 -0.004208 -0.002549 -0.010569 0.010186 0.294030 10.093431\n13290 51.200701 -0.003602 -0.002439 -0.010713 -0.000163 0.293701 10.107225\n13291 51.206850 -0.003421 -0.002500 -0.010688 0.002178 0.285430 10.101501\n13292 51.212836 -0.004137 -0.002226 -0.010627 0.005549 0.282353 10.083076\n13293 51.218854 -0.004416 -0.002232 -0.010603 0.004777 0.287027 10.083214\n13294 51.224952 -0.004292 -0.002908 -0.010266 0.007047 0.277126 10.108599\n13295 51.230923 -0.003989 -0.003115 -0.010171 0.005671 0.276112 10.111590\n13296 51.236946 -0.003875 -0.002775 -0.010260 -0.001319 0.296354 10.102013\n13297 51.242934 -0.003700 -0.002774 -0.010188 -0.008830 0.314840 10.103440\n13298 51.249164 -0.002978 -0.001526 -0.010212 -0.009348 0.304528 10.118271\n13299 51.255270 -0.003308 -0.001180 -0.010468 -0.008327 0.287623 10.121297\n13300 51.261242 -0.004550 -0.001984 -0.010458 0.006354 0.296986 10.116410\n13301 51.267177 -0.004601 -0.002413 -0.010255 0.010946 0.298698 10.115949\n13302 51.273314 -0.004440 -0.002874 -0.009768 0.006829 0.287526 10.092964\n13303 51.279202 -0.004340 -0.002942 -0.009686 0.003570 0.279945 10.070535\n13304 51.285397 -0.004530 -0.002396 -0.009458 0.004602 0.289455 10.068983\n13305 51.291257 -0.004403 -0.001856 -0.009455 0.003373 0.295473 10.083138\n13306 51.297462 -0.004178 -0.001435 -0.010496 -0.011385 0.272355 10.094007\n13307 51.303457 -0.004438 -0.001623 -0.010813 -0.010838 0.268976 10.088881\n13308 51.309463 -0.004073 -0.001470 -0.010604 -0.000027 0.299834 10.064537\n13309 51.316032 -0.003525 -0.001462 -0.010169 0.005453 0.302476 10.069022\n13310 51.321586 -0.003009 -0.002375 -0.009425 0.005759 0.277090 10.090971\n13311 51.327503 -0.003439 -0.002659 -0.009372 -0.001852 0.274021 10.098825\n13312 51.333568 -0.004571 -0.002505 -0.009886 -0.006053 0.309093 10.100146\n13313 51.340150 -0.004589 -0.002274 -0.010257 -0.003978 0.304725 10.089902\n13314 51.345871 -0.005185 -0.001912 -0.010596 0.010296 0.285031 10.094959\n13315 51.352179 -0.005368 -0.002040 -0.010618 0.011535 0.291571 10.103775\n13316 51.357949 -0.004546 -0.002328 -0.010010 0.005507 0.294735 10.102896\n13317 51.364461 -0.003980 -0.002700 -0.009316 0.006383 0.285403 10.089361\n13318 51.370049 -0.003743 -0.002841 -0.008994 0.003010 0.283724 10.094172\n13319 51.376596 -0.003191 -0.002820 -0.009337 0.006875 0.303398 10.107050\n13320 51.382060 -0.003132 -0.002618 -0.009835 0.007925 0.303322 10.108119\n13321 51.388426 -0.003415 -0.001916 -0.010268 0.015334 0.283845 10.075066\n13322 51.394088 -0.003737 -0.001343 -0.010253 0.016710 0.283845 10.074153\n13323 51.400544 -0.003709 -0.001417 -0.009516 0.021659 0.299307 10.094606\n13324 51.406346 -0.003098 -0.001747 -0.009008 0.026069 0.287171 10.102061\n13325 51.412426 -0.002990 -0.002208 -0.009085 0.027062 0.264666 10.093052\n13326 51.418260 -0.003818 -0.002322 -0.009437 0.014656 0.265942 10.093488\n13327 51.424297 -0.004125 -0.002149 -0.010711 -0.001253 0.287662 10.117303\n13328 51.430172 -0.003919 -0.002085 -0.010926 -0.000226 0.280121 10.126203\n13329 51.436650 -0.004834 -0.002140 -0.010859 0.014821 0.270776 10.104999\n13330 51.442285 -0.004836 -0.002161 -0.011003 0.013024 0.286478 10.088285\n13331 51.448409 -0.004103 -0.002571 -0.010769 0.009055 0.296471 10.114264\n13332 51.454380 -0.003797 -0.002946 -0.010453 0.007603 0.292791 10.119841\n13333 51.460515 -0.004066 -0.003121 -0.010172 0.007950 0.291797 10.100519\n13334 51.466505 -0.004400 -0.002965 -0.009888 0.009570 0.303269 10.093294\n13335 51.472647 -0.003990 -0.001892 -0.009430 0.004988 0.312402 10.109398\n13336 51.478674 -0.003535 -0.001496 -0.009669 0.004857 0.306367 10.117633\n13337 51.484730 -0.003382 -0.001774 -0.010525 0.007951 0.307751 10.112411\n13338 51.490612 -0.003505 -0.001989 -0.010602 0.010414 0.317840 10.106007\n13339 51.496728 -0.003355 -0.002522 -0.009582 0.015577 0.294663 10.082626\n13340 51.502770 -0.003575 -0.002800 -0.009290 0.008832 0.269331 10.069976\n13341 51.508767 -0.004421 -0.003054 -0.009139 -0.007959 0.267322 10.077265\n13342 51.514713 -0.004424 -0.002710 -0.009173 -0.010694 0.284395 10.078798\n13343 51.520787 -0.003724 -0.001519 -0.009424 -0.005355 0.280123 10.071704\n13344 51.527040 -0.003763 -0.001177 -0.009496 -0.005267 0.268059 10.064044\n13345 51.532920 -0.004291 -0.001085 -0.009807 0.003909 0.298011 10.067458\n13346 51.538900 -0.004102 -0.001011 -0.010007 0.015112 0.310238 10.081174\n13347 51.545116 -0.003811 -0.001597 -0.009777 0.019604 0.294376 10.097623\n13348 51.551035 -0.003821 -0.001994 -0.009810 0.013388 0.291484 10.098433\n13349 51.557265 -0.003711 -0.002271 -0.010087 0.010031 0.304763 10.103948\n13350 51.563039 -0.003591 -0.002375 -0.010294 0.010995 0.304403 10.109176\n13351 51.569444 -0.004058 -0.002385 -0.010410 0.021983 0.293032 10.113281\n13352 51.575260 -0.004414 -0.002553 -0.010276 0.023812 0.291146 10.106258\n13353 51.581281 -0.004444 -0.003053 -0.009914 0.011736 0.308326 10.102960\n13354 51.587421 -0.004198 -0.002951 -0.010075 0.007447 0.308994 10.104071\n13355 51.593259 -0.004300 -0.002512 -0.010046 0.008322 0.290060 10.098111\n13356 51.599215 -0.004265 -0.002641 -0.009821 0.001487 0.295548 10.100011\n13357 51.605388 -0.004324 -0.003456 -0.009599 0.011297 0.324165 10.103955\n13358 51.611482 -0.004302 -0.003202 -0.009916 0.008332 0.317176 10.105084\n13359 51.617607 -0.003912 -0.002104 -0.010430 0.001000 0.290229 10.096255\n13360 51.623503 -0.004069 -0.001875 -0.010547 0.003028 0.294619 10.092631\n13361 51.629500 -0.004304 -0.002049 -0.010260 0.015534 0.300369 10.082635\n13362 51.635501 -0.004471 -0.002239 -0.010129 0.015598 0.292966 10.077058\n13363 51.641535 -0.004216 -0.002948 -0.010011 -0.005539 0.282555 10.068515\n13364 51.647710 -0.003946 -0.003171 -0.009810 -0.005536 0.291717 10.084025\n13365 51.653809 -0.003394 -0.002919 -0.009735 0.004878 0.303712 10.104318\n13366 51.659772 -0.003408 -0.002540 -0.010049 -0.001132 0.292058 10.100905\n13367 51.665959 -0.004397 -0.001858 -0.010813 -0.001236 0.291008 10.098184\n13368 51.671833 -0.004756 -0.001601 -0.010676 -0.002086 0.301746 10.100566\n13369 51.678052 -0.004470 -0.001764 -0.010210 0.001051 0.303283 10.101704\n13370 51.683961 -0.004418 -0.002186 -0.009861 0.001903 0.286303 10.099387\n13371 51.690057 -0.005213 -0.002889 -0.009086 -0.007524 0.282109 10.090518\n13372 51.696049 -0.005129 -0.003003 -0.008843 -0.014503 0.296671 10.091774\n13373 51.702334 -0.004651 -0.002340 -0.009535 -0.019898 0.299613 10.097087\n13374 51.708705 -0.004807 -0.002321 -0.009970 -0.001207 0.291888 10.096299\n13375 51.714160 -0.005088 -0.002444 -0.010409 0.004827 0.299197 10.085115\n13376 51.720658 -0.005058 -0.002354 -0.010630 0.015991 0.302637 10.097293\n13377 51.726293 -0.004120 -0.002036 -0.010606 0.028749 0.293192 10.112888\n13378 51.732783 -0.004289 -0.001799 -0.010061 0.018832 0.294899 10.113011\n13379 51.738270 -0.004334 -0.001588 -0.009762 0.009590 0.306851 10.104712\n13380 51.744816 -0.004037 -0.001374 -0.010028 0.004496 0.314173 10.107546\n13381 51.750423 -0.003750 -0.001342 -0.010273 0.002611 0.304765 10.106010\n13382 51.756839 -0.003628 -0.001280 -0.010572 0.010382 0.297269 10.107332\n13383 51.762458 -0.003922 -0.001304 -0.010740 0.018135 0.296306 10.114711\n13384 51.769051 -0.004347 -0.001861 -0.010406 0.007858 0.281660 10.126913\n13385 51.774586 -0.004315 -0.001905 -0.010086 0.002804 0.271603 10.116997\n13386 51.780929 -0.004258 -0.002222 -0.009662 -0.008408 0.287132 10.092973\n13387 51.786603 -0.004156 -0.002674 -0.009731 -0.011980 0.301904 10.095922\n13388 51.792801 -0.003911 -0.002626 -0.009826 -0.015446 0.296486 10.101903\n13389 51.798693 -0.003883 -0.002090 -0.009902 -0.008404 0.284008 10.094774\n13390 51.804754 -0.004130 -0.001471 -0.010392 -0.002975 0.303791 10.079699\n13391 51.810940 -0.003695 -0.001346 -0.010622 -0.006910 0.315149 10.088011\n13392 51.816934 -0.002814 -0.002120 -0.010358 -0.009076 0.299520 10.093316\n13393 51.822893 -0.002975 -0.002686 -0.009982 -0.013628 0.295514 10.088377\n13394 51.828990 -0.003571 -0.003443 -0.009603 -0.023785 0.308533 10.102024\n13395 51.834933 -0.003603 -0.003685 -0.009688 -0.019184 0.306031 10.105177\n13396 51.841147 -0.003584 -0.003641 -0.009763 -0.013394 0.290356 10.117229\n13397 51.846948 -0.003349 -0.003680 -0.009949 -0.007265 0.294582 10.120605\n13398 51.853031 -0.003482 -0.003426 -0.010461 0.008849 0.299273 10.127565\n13399 51.859051 -0.003794 -0.003121 -0.010473 0.011879 0.294092 10.128762\n13400 51.865317 -0.003555 -0.002890 -0.010460 0.006076 0.280688 10.127095\n13401 51.871087 -0.003238 -0.002993 -0.010219 0.001999 0.287043 10.119798\n13402 51.877299 -0.003037 -0.003187 -0.010216 -0.006882 0.300878 10.112161\n13403 51.883209 -0.002978 -0.002953 -0.010301 -0.003040 0.291145 10.117227\n13404 51.889317 -0.003578 -0.001561 -0.010347 0.006343 0.285015 10.124435\n13405 51.895296 -0.003759 -0.001407 -0.010461 0.006416 0.299976 10.124887\n13406 51.901390 -0.003958 -0.001530 -0.010549 0.013698 0.307215 10.120839\n13407 51.907506 -0.003990 -0.001689 -0.010328 0.010454 0.304840 10.117667\n13408 51.913307 -0.004047 -0.002709 -0.008955 0.005791 0.296693 10.120800\n13409 51.919456 -0.004092 -0.003300 -0.008662 0.002284 0.301540 10.118234\n13410 51.925400 -0.004056 -0.003496 -0.009213 -0.004693 0.305434 10.112652\n13411 51.931545 -0.003590 -0.003056 -0.009356 -0.005800 0.297991 10.111963\n13412 51.937534 -0.003303 -0.003007 -0.010125 0.002502 0.303546 10.100349\n13413 51.943546 -0.003175 -0.002929 -0.010439 0.007739 0.309731 10.094098\n13414 51.949570 -0.003296 -0.002847 -0.010195 0.014943 0.292248 10.107309\n13415 51.955631 -0.003539 -0.003006 -0.009407 0.015149 0.283229 10.113015\n13416 51.961671 -0.003671 -0.002986 -0.008441 0.021676 0.308754 10.090832\n13417 51.967816 -0.003899 -0.002620 -0.008694 0.021524 0.317676 10.080901\n13418 51.973952 -0.004130 -0.002314 -0.010010 0.014216 0.294823 10.069448\n13419 51.979757 -0.004101 -0.002723 -0.010436 0.008113 0.280075 10.079216\n13420 51.985844 -0.004617 -0.003008 -0.010690 -0.000896 0.305243 10.098781\n13421 51.991923 -0.004872 -0.002365 -0.010627 -0.002559 0.315509 10.100366\n13422 51.997986 -0.004640 -0.001914 -0.010401 0.006734 0.290318 10.105440\n13423 52.003875 -0.004131 -0.002277 -0.010153 0.003396 0.283409 10.107539\n13424 52.009933 -0.003569 -0.002796 -0.009608 0.010947 0.301142 10.115219\n13425 52.016034 -0.003721 -0.002944 -0.009673 0.016844 0.308736 10.113981\n13426 52.022027 -0.003977 -0.002578 -0.010292 0.013077 0.314483 10.095811\n13427 52.028094 -0.004245 -0.002012 -0.010247 0.005881 0.316062 10.083325\n13428 52.034254 -0.004318 -0.001029 -0.009860 0.002404 0.306894 10.085428\n13429 52.040236 -0.003874 -0.001494 -0.009725 0.001527 0.298196 10.092049\n13430 52.046237 -0.003589 -0.002742 -0.009537 0.008801 0.279723 10.097286\n13431 52.052237 -0.003723 -0.002911 -0.009362 0.016818 0.280027 10.099769\n13432 52.058230 -0.003745 -0.003046 -0.008924 0.008286 0.299213 10.117783\n13433 52.064379 -0.003858 -0.003133 -0.009291 0.006848 0.301294 10.114137\n13434 52.070363 -0.004648 -0.002883 -0.010659 0.012876 0.304962 10.100842\n13435 52.076344 -0.004473 -0.002255 -0.011066 0.008940 0.299969 10.096882\n13436 52.082439 -0.003834 -0.001541 -0.011214 0.006851 0.286204 10.094610\n13437 52.088504 -0.004068 -0.001343 -0.010963 0.011820 0.276512 10.099271\n13438 52.094802 -0.004807 -0.002263 -0.010363 0.013539 0.276704 10.111031\n13439 52.100765 -0.004956 -0.003049 -0.009921 0.008838 0.283539 10.110600\n13440 52.106600 -0.004166 -0.004100 -0.009664 -0.004083 0.303442 10.101272\n13441 52.112567 -0.004030 -0.003648 -0.009523 -0.008141 0.302110 10.102343\n13442 52.119014 -0.004734 -0.002607 -0.009558 0.007221 0.306966 10.108067\n13443 52.124783 -0.005055 -0.002405 -0.010065 0.010493 0.319202 10.107947\n13444 52.130906 -0.005016 -0.002505 -0.011167 0.004190 0.305657 10.099590\n13445 52.136780 -0.004796 -0.002454 -0.011037 0.003917 0.287596 10.089526\n13446 52.142910 -0.004422 -0.002963 -0.010185 0.001515 0.292335 10.080005\n13447 52.149407 -0.004033 -0.003168 -0.009833 0.004260 0.306035 10.076326\n13448 52.156618 -0.003274 -0.003022 -0.009693 0.002956 0.311366 10.087794\n13449 52.161554 -0.003892 -0.002044 -0.010411 -0.012888 0.324152 10.101819\n13450 52.167311 -0.004100 -0.001575 -0.010782 -0.014542 0.331029 10.105639\n13451 52.173702 -0.003877 -0.001014 -0.010850 -0.001700 0.317050 10.108757\n13452 52.179255 -0.003474 -0.001494 -0.010578 -0.000173 0.305938 10.103889\n13453 52.185526 -0.003333 -0.002401 -0.009903 0.008660 0.290861 10.090368\n13454 52.191521 -0.002955 -0.002885 -0.009675 0.008900 0.289480 10.091390\n13455 52.197788 -0.002906 -0.003143 -0.009687 -0.006008 0.293747 10.101438\n13456 52.203382 -0.003319 -0.003228 -0.010167 -0.009439 0.288507 10.102963\n13457 52.209657 -0.004437 -0.002875 -0.010730 0.004715 0.302285 10.099067\n13458 52.215515 -0.004674 -0.003000 -0.010643 0.012306 0.306560 10.101302\n13459 52.222011 -0.004373 -0.002964 -0.009988 0.015540 0.288483 10.077058\n13460 52.227517 -0.004315 -0.003096 -0.009489 0.018750 0.290871 10.062636\n13461 52.234012 -0.004622 -0.003326 -0.009144 0.026043 0.309514 10.069262\n13462 52.239650 -0.004449 -0.002978 -0.009464 0.031886 0.312111 10.087003\n13463 52.245717 -0.004064 -0.002273 -0.010104 0.020533 0.297157 10.117611\n13464 52.251576 -0.004196 -0.002308 -0.010124 0.005527 0.299339 10.113852\n13465 52.257862 -0.004438 -0.002249 -0.010606 0.002437 0.313628 10.103854\n13466 52.263787 -0.004429 -0.002120 -0.010687 0.011064 0.302028 10.084471\n13467 52.269764 -0.004474 -0.001811 -0.010636 0.020734 0.281738 10.053207\n13468 52.275784 -0.004565 -0.002040 -0.010371 0.022892 0.278364 10.048054\n13469 52.282045 -0.004099 -0.003027 -0.010070 0.021325 0.280134 10.055115\n13470 52.287756 -0.003913 -0.003516 -0.009683 0.018535 0.285534 10.061238\n13471 52.293885 -0.004194 -0.003494 -0.009263 0.001465 0.285949 10.082480\n13472 52.299913 -0.004480 -0.003142 -0.009486 -0.003583 0.288218 10.090098\n13473 52.306000 -0.004292 -0.002356 -0.009713 0.002045 0.300412 10.089449\n13474 52.312133 -0.004167 -0.002435 -0.009900 0.012309 0.291222 10.093648\n13475 52.318026 -0.004611 -0.002913 -0.010354 0.016154 0.272525 10.095583\n13476 52.324090 -0.004996 -0.002746 -0.010507 0.011291 0.280616 10.091609\n13477 52.330158 -0.004909 -0.002572 -0.010102 -0.000185 0.297487 10.103476\n13478 52.336128 -0.004518 -0.002508 -0.010048 -0.004851 0.299471 10.106593\n13479 52.342296 -0.004261 -0.002197 -0.010403 -0.011610 0.316017 10.099422\n13480 52.348127 -0.004182 -0.002042 -0.010737 -0.008365 0.321112 10.109106\n13481 52.354263 -0.003670 -0.001563 -0.010892 0.011564 0.293191 10.108428\n13482 52.360296 -0.003847 -0.001693 -0.010398 0.020182 0.274576 10.110318\n13483 52.366499 -0.004445 -0.001901 -0.009261 0.011168 0.279124 10.103090\n13484 52.372507 -0.004338 -0.002076 -0.009147 0.002717 0.290055 10.098083\n13485 52.378328 -0.003712 -0.002848 -0.009291 -0.005561 0.301604 10.089737\n13486 52.384461 -0.003643 -0.002967 -0.009420 -0.004243 0.298114 10.091764\n13487 52.390500 -0.003588 -0.002581 -0.010150 -0.011640 0.311023 10.094281\n13488 52.396512 -0.003745 -0.002421 -0.010607 -0.005541 0.317996 10.102775\n13489 52.402664 -0.003894 -0.001665 -0.010960 0.011403 0.302617 10.097854\n13490 52.408635 -0.003975 -0.001497 -0.010761 0.017698 0.289869 10.097778\n13491 52.414638 -0.004465 -0.002116 -0.009871 0.015857 0.312614 10.098554\n13492 52.420669 -0.004563 -0.002374 -0.009366 0.018408 0.324822 10.106637\n13493 52.426651 -0.004205 -0.002365 -0.009109 0.007990 0.305905 10.107528\n13494 52.432879 -0.004303 -0.001882 -0.009259 -0.004342 0.301411 10.106483\n13495 52.438741 -0.004700 -0.000895 -0.009814 -0.008018 0.317965 10.116312\n13496 52.444792 -0.004258 -0.000868 -0.010249 -0.004668 0.323601 10.121991\n13497 52.450778 -0.003566 -0.001239 -0.010798 0.003550 0.301611 10.112180\n13498 52.457011 -0.003517 -0.001737 -0.010521 0.004301 0.300911 10.107410\n13499 52.463044 -0.003696 -0.002480 -0.010427 0.009335 0.323440 10.096437\n13500 52.469009 -0.003575 -0.002874 -0.010335 0.012236 0.319225 10.092162\n13501 52.475005 -0.004191 -0.002792 -0.010024 0.005871 0.290617 10.085900\n13502 52.481168 -0.004310 -0.002405 -0.010282 0.001837 0.295708 10.087105\n13503 52.487038 -0.003864 -0.002308 -0.010900 0.003386 0.304387 10.100226\n13504 52.493247 -0.004002 -0.002466 -0.011046 0.008179 0.302249 10.098288\n13505 52.499436 -0.004607 -0.002113 -0.010922 0.010684 0.287430 10.080144\n13506 52.505292 -0.004666 -0.002248 -0.010581 -0.000083 0.290931 10.078023\n13507 52.511259 -0.004448 -0.003117 -0.009527 -0.016871 0.310507 10.093915\n13508 52.517317 -0.004312 -0.003406 -0.009375 -0.017969 0.303833 10.095798\n13509 52.523417 -0.004509 -0.003336 -0.009721 -0.023413 0.292571 10.095213\n13510 52.529422 -0.004445 -0.002754 -0.010145 -0.014770 0.301846 10.101777\n13511 52.535434 -0.003976 -0.001595 -0.010381 0.005039 0.288295 10.127857\n13512 52.541541 -0.003857 -0.001164 -0.010203 0.006073 0.274059 10.116538\n13513 52.547529 -0.003949 -0.001765 -0.009690 0.002302 0.282012 10.080527\n13514 52.553634 -0.003970 -0.002337 -0.009603 0.004596 0.289093 10.076792\n13515 52.559569 -0.003546 -0.002958 -0.009769 0.016036 0.289989 10.088992\n13516 52.565632 -0.003215 -0.003256 -0.009705 0.014253 0.285139 10.095615\n13517 52.571779 -0.003145 -0.003362 -0.010019 -0.004722 0.293824 10.099936\n13518 52.577863 -0.003135 -0.003019 -0.010318 -0.010484 0.316124 10.091600\n13519 52.583917 -0.003417 -0.002016 -0.010611 0.001029 0.319543 10.078029\n13520 52.589881 -0.003495 -0.001358 -0.010539 0.012302 0.307483 10.070498\n13521 52.595916 -0.003978 -0.001326 -0.009849 0.022398 0.308153 10.087074\n13522 52.601910 -0.004026 -0.001838 -0.009628 0.015971 0.306199 10.096997\n13523 52.608043 -0.003353 -0.002797 -0.009931 0.011634 0.273808 10.086689\n13524 52.614040 -0.003385 -0.002909 -0.010115 0.001419 0.274011 10.074979\n13525 52.620084 -0.003631 -0.002843 -0.010493 -0.002145 0.311517 10.078028\n13526 52.626590 -0.003813 -0.002556 -0.010585 0.008866 0.309613 10.092255\n13527 52.632411 -0.004236 -0.002517 -0.010373 0.024852 0.282841 10.086338\n13528 52.638637 -0.004256 -0.002580 -0.010011 0.024982 0.282509 10.086227\n13529 52.644280 -0.004057 -0.003410 -0.009302 0.012619 0.294680 10.103650\n13530 52.650683 -0.003612 -0.003104 -0.009048 0.008252 0.280623 10.096540\n13531 52.657182 -0.003840 -0.002645 -0.009627 0.010960 0.278251 10.088990\n13532 52.662754 -0.003948 -0.001862 -0.010826 0.002969 0.311019 10.077628\n13533 52.668233 -0.003644 -0.001699 -0.010639 -0.001533 0.323304 10.080090\n13534 52.674892 -0.003806 -0.002011 -0.010391 0.010949 0.297369 10.078936\n13535 52.680353 -0.004277 -0.002359 -0.010503 0.015067 0.277965 10.079424\n13536 52.686745 -0.004479 -0.002912 -0.010014 0.019178 0.293255 10.100838\n13537 52.692412 -0.003969 -0.003056 -0.010059 0.019723 0.305841 10.119173\n13538 52.698861 -0.003551 -0.002306 -0.009951 0.006240 0.298752 10.124758\n13539 52.704585 -0.003960 -0.001817 -0.009782 -0.008947 0.303912 10.126545\n13540 52.710722 -0.004134 -0.001561 -0.009690 -0.011469 0.326797 10.129540\n13541 52.716568 -0.004019 -0.001798 -0.009611 -0.002601 0.320899 10.129972\n13542 52.722820 -0.004514 -0.001934 -0.009857 0.006803 0.284791 10.114351\n13543 52.728549 -0.004495 -0.002408 -0.010013 0.015741 0.285659 10.100938\n13544 52.735181 -0.004287 -0.003240 -0.009730 0.011423 0.314701 10.098297\n13545 52.740701 -0.004305 -0.003170 -0.009447 0.013769 0.312410 10.093458\n13546 52.746898 -0.003743 -0.002318 -0.009448 0.005044 0.301436 10.066455\n13547 52.752823 -0.003506 -0.002145 -0.010148 -0.002674 0.305379 10.068926\n13548 52.758798 -0.004263 -0.001268 -0.011352 -0.007138 0.313894 10.097193\n13549 52.765213 -0.004266 -0.001125 -0.011310 -0.001079 0.301731 10.106581\n13550 52.770977 -0.004332 -0.001422 -0.010862 0.024861 0.284458 10.119376\n13551 52.777264 -0.004595 -0.001828 -0.010643 0.018608 0.299001 10.120542\n13552 52.783126 -0.004377 -0.002064 -0.009744 -0.006408 0.315598 10.116557\n13553 52.789254 -0.004167 -0.001881 -0.009528 -0.006752 0.305406 10.108058\n13554 52.795248 -0.004398 -0.000985 -0.009714 0.004988 0.289120 10.094870\n13555 52.801206 -0.004532 -0.000775 -0.009925 0.007128 0.304707 10.101163\n13556 52.807174 -0.003775 -0.000520 -0.010871 0.006209 0.310289 10.111387\n13557 52.813195 -0.003375 -0.000884 -0.010969 0.011304 0.297057 10.107696\n13558 52.819181 -0.003115 -0.002077 -0.010764 0.018300 0.283439 10.090676\n13559 52.825406 -0.003372 -0.002703 -0.010578 0.012405 0.293621 10.084139\n13560 52.831391 -0.004032 -0.002769 -0.009829 0.009914 0.306487 10.074481\n13561 52.837331 -0.004396 -0.002139 -0.009606 0.008167 0.301225 10.077169\n13562 52.843413 -0.004603 -0.001509 -0.009858 0.020942 0.320910 10.101589\n13563 52.849386 -0.004597 -0.001165 -0.009915 0.026483 0.327360 10.105203\n13564 52.855569 -0.004139 -0.001114 -0.010124 0.023067 0.293889 10.111428\n13565 52.861511 -0.004384 -0.001177 -0.010308 0.018880 0.273602 10.094642\n13566 52.867598 -0.004389 -0.001883 -0.010222 0.006254 0.288196 10.070671\n13567 52.873518 -0.004068 -0.002447 -0.009928 0.004733 0.302889 10.072053\n13568 52.879540 -0.003580 -0.002595 -0.009491 0.013103 0.286453 10.095497\n13569 52.885734 -0.004068 -0.002494 -0.009950 0.011981 0.282429 10.096542\n13570 52.891792 -0.004641 -0.002347 -0.010655 0.011869 0.309595 10.085532\n13571 52.897883 -0.004211 -0.002286 -0.011086 0.015975 0.314694 10.089669\n13572 52.903672 -0.003628 -0.002022 -0.011008 0.029947 0.294682 10.103987\n13573 52.909853 -0.003718 -0.002001 -0.010540 0.028191 0.294882 10.106397\n13574 52.915902 -0.004008 -0.002168 -0.010160 0.015247 0.309669 10.115521\n13575 52.922014 -0.003867 -0.002267 -0.009884 0.001942 0.298579 10.111877\n13576 52.927926 -0.003915 -0.002442 -0.010077 -0.004900 0.286587 10.097273\n13577 52.934005 -0.004395 -0.002746 -0.010171 -0.003681 0.303298 10.100203\n13578 52.939891 -0.004182 -0.002808 -0.010049 -0.011796 0.326503 10.105323\n13579 52.946102 -0.003617 -0.002438 -0.010186 -0.013135 0.312931 10.105437\n13580 52.951958 -0.004074 -0.002328 -0.010263 0.004976 0.281216 10.087451\n13581 52.958095 -0.004563 -0.002331 -0.010222 0.009115 0.284856 10.086889\n13582 52.964269 -0.004194 -0.002294 -0.010336 0.009461 0.289115 10.101530\n13583 52.970248 -0.003763 -0.002257 -0.010282 0.003600 0.281676 10.101556\n13584 52.976377 -0.004411 -0.002559 -0.010083 0.004703 0.298106 10.089963\n13585 52.982255 -0.004432 -0.002500 -0.010164 0.010588 0.313563 10.097848\n13586 52.988379 -0.003689 -0.002326 -0.010493 0.011642 0.308828 10.103968\n13587 52.994338 -0.003272 -0.002160 -0.010585 0.008373 0.296631 10.102220\n13588 53.000519 -0.003651 -0.002222 -0.010627 0.019894 0.299425 10.096173\n13589 53.006478 -0.003956 -0.002534 -0.010582 0.026412 0.311766 10.099568\n13590 53.012482 -0.004692 -0.003494 -0.009832 0.020668 0.314731 10.102575\n13591 53.018506 -0.004519 -0.003421 -0.009491 0.015704 0.306351 10.101488\n13592 53.024480 -0.004230 -0.002840 -0.009707 -0.000203 0.314235 10.082622\n13593 53.030740 -0.004379 -0.002331 -0.010025 -0.002388 0.320298 10.093056\n13594 53.036743 -0.004183 -0.001622 -0.010347 0.009361 0.295923 10.119015\n13595 53.043223 -0.004105 -0.001632 -0.010123 0.012482 0.280453 10.112894\n13596 53.048938 -0.004488 -0.002483 -0.010140 0.012608 0.296932 10.096567\n13597 53.054803 -0.004273 -0.003049 -0.009946 0.009183 0.303544 10.105309\n13598 53.060804 -0.003762 -0.002960 -0.010042 0.004428 0.289366 10.112747\n13599 53.067692 -0.004313 -0.002359 -0.010478 0.004009 0.290382 10.100202\n13600 53.072926 -0.004382 -0.002049 -0.010560 0.003920 0.303177 10.100827\n13601 53.079567 -0.003750 -0.001779 -0.010722 0.000818 0.306142 10.093636\n13602 53.085084 -0.003450 -0.001817 -0.010701 0.003347 0.285999 10.084564\n13603 53.091699 -0.003697 -0.002458 -0.010751 0.017319 0.296180 10.095047\n13604 53.097359 -0.003649 -0.002672 -0.010679 0.025126 0.311425 10.094220\n13605 53.103689 -0.003619 -0.002961 -0.010377 0.025338 0.304327 10.075104\n13606 53.109217 -0.003913 -0.002847 -0.010145 0.023186 0.291455 10.071342\n13607 53.115654 -0.004729 -0.002467 -0.009803 0.022887 0.302251 10.077061\n13608 53.121268 -0.004648 -0.002357 -0.009803 0.020093 0.312396 10.095871\n13609 53.127659 -0.004171 -0.001398 -0.010134 0.009099 0.283001 10.123302\n13610 53.133270 -0.004029 -0.001292 -0.010207 0.012830 0.273206 10.113990\n13611 53.139649 -0.004466 -0.002788 -0.010033 0.016093 0.308051 10.096916\n13612 53.145331 -0.004511 -0.003484 -0.009981 0.013573 0.310915 10.096587\n13613 53.151653 -0.003487 -0.003742 -0.010383 0.007198 0.282010 10.089849\n13614 53.157549 -0.003351 -0.003489 -0.010536 0.003670 0.285402 10.093821\n13615 53.163828 -0.003393 -0.002790 -0.010601 0.005785 0.311144 10.101027\n13616 53.169408 -0.003242 -0.002815 -0.010304 0.017804 0.308659 10.099921\n13617 53.175694 -0.003398 -0.002627 -0.009858 0.043141 0.291625 10.082464\n13618 53.181594 -0.003710 -0.002722 -0.009906 0.044705 0.291035 10.087806\n13619 53.187958 -0.004486 -0.002984 -0.009675 0.027004 0.296478 10.105750\n13620 53.193700 -0.004573 -0.003119 -0.009587 0.020887 0.296434 10.109219\n13621 53.199653 -0.004553 -0.002837 -0.009558 0.012688 0.290590 10.093953\n13622 53.205824 -0.004550 -0.002590 -0.009761 0.001311 0.300403 10.085027\n13623 53.211655 -0.004379 -0.001813 -0.010122 -0.009583 0.321886 10.092053\n13624 53.217839 -0.004072 -0.001361 -0.010271 -0.006580 0.308614 10.094213\n13625 53.223812 -0.004029 -0.001147 -0.009835 0.007057 0.287397 10.090307\n13626 53.229979 -0.004264 -0.001222 -0.009638 0.013881 0.298774 10.094261\n13627 53.235971 -0.003244 -0.002387 -0.009522 0.018550 0.302179 10.115624\n13628 53.241861 -0.003048 -0.003336 -0.009532 0.018988 0.284764 10.103831\n13629 53.248179 -0.003920 -0.004388 -0.009855 0.008922 0.293630 10.072130\n13630 53.253961 -0.004391 -0.004231 -0.009992 0.000672 0.310408 10.062655\n13631 53.260185 -0.004114 -0.003371 -0.010097 -0.002733 0.308012 10.075582\n13632 53.266129 -0.004060 -0.003197 -0.009880 0.005663 0.297639 10.085307\n13633 53.272320 -0.004446 -0.003319 -0.009575 0.019649 0.316170 10.078915\n13634 53.278138 -0.004665 -0.003559 -0.009524 0.013672 0.330176 10.080478\n13635 53.284244 -0.004998 -0.003709 -0.010038 0.002405 0.317498 10.085898\n13636 53.290273 -0.004965 -0.003587 -0.010311 0.008614 0.298977 10.087381\n13637 53.296505 -0.004665 -0.003329 -0.009980 0.020278 0.302806 10.101649\n13638 53.302300 -0.004363 -0.002921 -0.010057 0.014684 0.310589 10.108890\n13639 53.308451 -0.003252 -0.001972 -0.010457 0.006104 0.301882 10.118209\n13640 53.314263 -0.003149 -0.001910 -0.010572 0.009791 0.300625 10.119273\n13641 53.320431 -0.003802 -0.002256 -0.010325 0.002520 0.315079 10.087920\n13642 53.326513 -0.004011 -0.002792 -0.010048 -0.004994 0.313217 10.087176\n13643 53.332428 -0.003934 -0.003052 -0.009869 -0.000574 0.287067 10.103155\n13644 53.338583 -0.004386 -0.002768 -0.009933 0.000325 0.293877 10.110901\n13645 53.344623 -0.004951 -0.002218 -0.010127 -0.009692 0.323752 10.125148\n13646 53.350708 -0.004838 -0.002138 -0.010182 -0.000315 0.325259 10.123784\n13647 53.356524 -0.005124 -0.002936 -0.009764 0.023320 0.298414 10.121739\n13648 53.362733 -0.005282 -0.002862 -0.009706 0.027156 0.286825 10.112661\n13649 53.368884 -0.005043 -0.002594 -0.010088 0.021391 0.298684 10.103662\n13650 53.374732 -0.004696 -0.002904 -0.009928 0.011049 0.304347 10.096795\n13651 53.380889 -0.003994 -0.002924 -0.009611 -0.002950 0.294507 10.088311\n13652 53.386902 -0.003743 -0.002941 -0.009649 -0.000128 0.298381 10.079482\n13653 53.392842 -0.003456 -0.002612 -0.009982 0.007889 0.332411 10.078400\n13654 53.398976 -0.003595 -0.002054 -0.010392 0.008737 0.333554 10.091663\n13655 53.405010 -0.003997 -0.001157 -0.010664 0.006251 0.300703 10.093070\n13656 53.411010 -0.004035 -0.001611 -0.010454 0.010348 0.308000 10.098039\n13657 53.417106 -0.003475 -0.002433 -0.009706 0.014738 0.325049 10.104634\n13658 53.423168 -0.002891 -0.002608 -0.009598 0.003430 0.317320 10.101223\n13659 53.429441 -0.003508 -0.002671 -0.009791 -0.009367 0.300121 10.093397\n13660 53.435293 -0.003876 -0.002301 -0.010110 -0.003153 0.311124 10.088731\n13661 53.441306 -0.004078 -0.001218 -0.010538 0.003937 0.325282 10.109621\n13662 53.447303 -0.004060 -0.001299 -0.010572 0.008258 0.317796 10.114581\n13663 53.453322 -0.004390 -0.002306 -0.010107 0.000700 0.319067 10.102541\n13664 53.459474 -0.004402 -0.002830 -0.010208 -0.004384 0.327402 10.109101\n13665 53.465345 -0.003941 -0.002832 -0.010269 -0.001366 0.309426 10.108257\n13666 53.471471 -0.003881 -0.002998 -0.010237 0.004724 0.287656 10.101275\n13667 53.477509 -0.004344 -0.002911 -0.009945 0.013836 0.291799 10.104024\n13668 53.483509 -0.004639 -0.002769 -0.009818 0.007677 0.311513 10.104082\n13669 53.489641 -0.004781 -0.002188 -0.009746 -0.002848 0.295229 10.112660\n13670 53.496007 -0.004721 -0.001997 -0.009637 -0.004157 0.285450 10.118071\n13671 53.501765 -0.004373 -0.001948 -0.009654 -0.003950 0.302201 10.119416\n13672 53.508219 -0.004106 -0.002003 -0.009697 -0.000100 0.309397 10.109577\n13673 53.513968 -0.003734 -0.001957 -0.009390 0.005312 0.295873 10.103662\n13674 53.520192 -0.003519 -0.002287 -0.009388 0.002580 0.312013 10.098494\n13675 53.525811 -0.003620 -0.002233 -0.009558 0.000306 0.325213 10.104681\n13676 53.532160 -0.003675 -0.001691 -0.010464 0.007745 0.312504 10.107197\n13677 53.537815 -0.003977 -0.001840 -0.010730 0.010224 0.296476 10.093830\n13678 53.544131 -0.004679 -0.002225 -0.010557 0.018187 0.290615 10.090858\n13679 53.549930 -0.004604 -0.002364 -0.010095 0.026902 0.303349 10.094594\n13680 53.556485 -0.004154 -0.002478 -0.009346 0.022150 0.310501 10.098951\n13681 53.562061 -0.004263 -0.002259 -0.009220 0.018309 0.304528 10.096881\n13682 53.568127 -0.004585 -0.002756 -0.009984 0.011554 0.312905 10.084566\n13683 53.574072 -0.004596 -0.002935 -0.010143 0.010581 0.321917 10.083816\n13684 53.580396 -0.004400 -0.002555 -0.010439 0.014597 0.301882 10.088202\n13685 53.586189 -0.004352 -0.002170 -0.010293 0.018969 0.294767 10.086605\n13686 53.592248 -0.004739 -0.001629 -0.010133 0.012267 0.305498 10.088214\n13687 53.598352 -0.004533 -0.001596 -0.009709 0.008874 0.304094 10.105500\n13688 53.604430 -0.003873 -0.002179 -0.009609 0.011469 0.281838 10.103753\n13689 53.610450 -0.003988 -0.002657 -0.009867 0.009212 0.277569 10.102184\n13690 53.616432 -0.004286 -0.003171 -0.010097 0.007321 0.305615 10.113812\n13691 53.622413 -0.004281 -0.002959 -0.009962 0.008676 0.320352 10.123543\n13692 53.628535 -0.004338 -0.002391 -0.009722 0.016023 0.321755 10.118231\n13693 53.634588 -0.004279 -0.002139 -0.009856 0.018418 0.316147 10.107682\n13694 53.640720 -0.004299 -0.002420 -0.009840 0.008692 0.318469 10.093975\n13695 53.646673 -0.004237 -0.002870 -0.009853 0.007698 0.311087 10.098293\n13696 53.652906 -0.003937 -0.002883 -0.009563 -0.001728 0.303008 10.099401\n13697 53.658634 -0.003950 -0.003013 -0.009507 -0.011529 0.303783 10.089097\n13698 53.664780 -0.003632 -0.002803 -0.009475 -0.006403 0.297988 10.066220\n13699 53.670860 -0.003537 -0.002475 -0.009720 0.006610 0.288367 10.066769\n13700 53.676761 -0.003706 -0.001916 -0.009884 0.016321 0.284334 10.078526\n13701 53.682782 -0.003744 -0.002180 -0.010132 0.014946 0.295468 10.082291\n13702 53.688841 -0.003693 -0.002486 -0.010379 0.010594 0.300808 10.092502\n13703 53.694994 -0.004220 -0.002542 -0.010298 0.005422 0.299677 10.094413\n13704 53.700985 -0.005119 -0.002729 -0.010235 0.002194 0.299673 10.104926\n13705 53.706921 -0.004671 -0.002705 -0.010387 0.010193 0.300999 10.109485\n13706 53.712992 -0.003438 -0.002793 -0.010764 0.018724 0.301293 10.111382\n13707 53.719019 -0.003422 -0.002718 -0.010952 0.011681 0.301148 10.103890\n13708 53.725137 -0.004209 -0.002536 -0.010010 0.004682 0.306071 10.104492\n13709 53.731255 -0.004420 -0.002500 -0.009780 0.007130 0.307185 10.120057\n13710 53.737137 -0.004373 -0.002390 -0.009679 0.004388 0.293826 10.123051\n13711 53.743194 -0.004222 -0.002201 -0.009883 0.000905 0.291986 10.114956\n13712 53.749208 -0.004180 -0.002207 -0.010171 -0.007736 0.306782 10.103052\n13713 53.755189 -0.004128 -0.002232 -0.009818 -0.005615 0.316425 10.113481\n13714 53.761334 -0.003995 -0.002267 -0.009566 0.015711 0.314801 10.133182\n13715 53.767429 -0.003933 -0.002416 -0.009830 0.025810 0.310793 10.129586\n13716 53.773394 -0.004252 -0.002847 -0.009708 0.025135 0.312362 10.104742\n13717 53.779578 -0.004228 -0.003106 -0.010142 0.023198 0.310615 10.112960\n13718 53.785494 -0.004368 -0.003483 -0.010461 0.012975 0.303382 10.135564\n13719 53.791579 -0.004252 -0.003584 -0.010251 0.007698 0.302071 10.141026\n13720 53.797473 -0.004042 -0.003060 -0.010223 0.005091 0.314204 10.108092\n13721 53.803493 -0.004014 -0.002395 -0.010288 0.009356 0.303607 10.096077\n13722 53.809572 -0.003940 -0.002027 -0.009913 0.025338 0.286064 10.075200\n13723 53.815510 -0.003850 -0.002156 -0.009729 0.028851 0.293084 10.084226\n13724 53.821826 -0.003900 -0.002516 -0.009889 0.017139 0.319889 10.110378\n13725 53.827859 -0.004050 -0.002847 -0.009877 0.012636 0.320213 10.106497\n13726 53.833817 -0.003665 -0.002676 -0.009848 0.006695 0.309004 10.087060\n13727 53.839911 -0.003628 -0.002501 -0.010155 0.005638 0.317372 10.084302\n13728 53.846009 -0.004312 -0.002673 -0.010467 0.016898 0.342508 10.112080\n13729 53.851952 -0.004460 -0.002533 -0.010198 0.023339 0.333241 10.133512\n13730 53.857763 -0.004289 -0.002356 -0.010091 0.021681 0.292093 10.125470\n13731 53.864068 -0.004244 -0.002577 -0.009898 0.010652 0.294948 10.106461\n13732 53.870077 -0.004001 -0.002965 -0.009763 0.000878 0.302853 10.095284\n13733 53.876103 -0.004174 -0.002949 -0.009886 0.009028 0.296054 10.091755\n13734 53.882297 -0.004687 -0.002540 -0.009687 0.007911 0.305732 10.101774\n13735 53.888305 -0.004832 -0.002405 -0.009589 0.005689 0.319710 10.117406\n13736 53.894355 -0.004009 -0.001956 -0.010042 0.007593 0.325582 10.133432\n13737 53.900261 -0.004004 -0.001965 -0.010342 0.014921 0.316464 10.124626\n13738 53.906201 -0.004538 -0.002236 -0.010611 0.006756 0.300849 10.110803\n13739 53.913065 -0.004514 -0.002473 -0.010637 -0.000789 0.307489 10.112618\n13740 53.918420 -0.003801 -0.002024 -0.010187 -0.003371 0.311864 10.109232\n13741 53.924737 -0.003540 -0.001870 -0.009863 0.000314 0.300455 10.108836\n13742 53.930548 -0.004234 -0.002439 -0.009868 0.019011 0.300899 10.083694\n13743 53.936955 -0.004327 -0.002991 -0.010145 0.017963 0.313808 10.073660\n13744 53.942769 -0.004238 -0.003047 -0.009888 0.000127 0.309430 10.102887\n13745 53.948930 -0.004064 -0.002743 -0.009795 -0.009431 0.296192 10.111983\n13746 53.954701 -0.004271 -0.002365 -0.009931 -0.007157 0.301007 10.118766\n13747 53.961199 -0.004116 -0.002225 -0.010118 0.006733 0.301312 10.107095\n13748 53.966827 -0.003990 -0.002215 -0.010350 0.014890 0.293930 10.101030\n13749 53.973377 -0.004352 -0.002452 -0.010200 0.020704 0.293404 10.111954\n13750 53.978904 -0.004456 -0.002658 -0.010206 0.011314 0.301512 10.114646\n13751 53.985242 -0.004862 -0.003057 -0.009786 0.010614 0.295135 10.117355\n13752 53.990785 -0.005027 -0.002893 -0.009454 0.010337 0.293210 10.106943\n13753 53.997286 -0.004903 -0.002460 -0.009908 -0.003275 0.303819 10.069926\n13754 54.002994 -0.004514 -0.002223 -0.010238 -0.008413 0.306967 10.064588\n13755 54.009310 -0.004506 -0.002002 -0.010526 -0.003456 0.311799 10.082027\n13756 54.015116 -0.004433 -0.001960 -0.010580 -0.000492 0.312317 10.082478\n13757 54.021291 -0.004004 -0.002372 -0.009856 0.005022 0.315878 10.107243\n13758 54.027353 -0.003933 -0.002571 -0.009654 0.005177 0.309837 10.110266\n13759 54.033480 -0.003941 -0.002429 -0.010027 0.004096 0.286728 10.090055\n13760 54.039222 -0.003952 -0.002484 -0.010241 0.006891 0.286418 10.085586\n13761 54.045283 -0.003618 -0.003010 -0.009910 0.005493 0.312569 10.086873\n13762 54.051281 -0.003699 -0.002725 -0.009798 0.008265 0.314284 10.086784\n13763 54.057537 -0.003755 -0.002176 -0.010280 0.019987 0.282719 10.088806\n13764 54.063404 -0.004063 -0.002505 -0.010482 0.024277 0.283763 10.095282\n13765 54.069319 -0.004398 -0.002813 -0.010379 0.007681 0.300783 10.114273\n13766 54.075331 -0.004383 -0.003011 -0.010197 0.003865 0.296386 10.098619\n13767 54.081400 -0.004115 -0.003409 -0.009979 0.017268 0.294655 10.071842\n13768 54.087674 -0.003702 -0.003426 -0.009772 0.017343 0.311110 10.072459\n13769 54.093947 -0.003116 -0.003318 -0.009863 -0.003756 0.322952 10.075453\n13770 54.099530 -0.002945 -0.002988 -0.009976 -0.007218 0.314077 10.076550\n13771 54.105641 -0.002849 -0.001770 -0.010332 -0.003841 0.290923 10.086839\n13772 54.111609 -0.003222 -0.001580 -0.010274 0.002984 0.290879 10.099782\n13773 54.117673 -0.004158 -0.002257 -0.010027 0.010650 0.305518 10.143244\n13774 54.123742 -0.004451 -0.002210 -0.010210 0.017301 0.299669 10.151835\n13775 54.129670 -0.004823 -0.002382 -0.010194 0.020493 0.305688 10.128710\n13776 54.135742 -0.004886 -0.002621 -0.010158 0.019945 0.319431 10.113084\n13777 54.141743 -0.003973 -0.002786 -0.010610 0.010276 0.319871 10.103842\n13778 54.147788 -0.003834 -0.002511 -0.010728 0.006492 0.300985 10.109908\n13779 54.153903 -0.004104 -0.002293 -0.010421 0.002950 0.295558 10.099489\n13780 54.159927 -0.004066 -0.002682 -0.010045 0.004390 0.308609 10.097071\n13781 54.165969 -0.003814 -0.002749 -0.009315 0.017978 0.316798 10.102326\n13782 54.171973 -0.003549 -0.002354 -0.009481 0.021489 0.304758 10.099516\n13783 54.177886 -0.004331 -0.002495 -0.010018 0.020226 0.297365 10.084565\n13784 54.184186 -0.004606 -0.002706 -0.010329 0.025289 0.301647 10.090298\n13785 54.190156 -0.003452 -0.002324 -0.010437 0.033183 0.293879 10.106860\n13786 54.196126 -0.003385 -0.002070 -0.010429 0.031621 0.291107 10.114446\n13787 54.202114 -0.003762 -0.002150 -0.010234 0.012166 0.310905 10.113035\n13788 54.208249 -0.003741 -0.002167 -0.010012 0.003932 0.320441 10.109227\n13789 54.214159 -0.003955 -0.002286 -0.009865 -0.000694 0.302759 10.115298\n13790 54.220375 -0.004138 -0.002489 -0.010140 0.002629 0.297320 10.118671\n13791 54.226334 -0.004750 -0.003380 -0.010063 -0.004171 0.322402 10.124001\n13792 54.232394 -0.004549 -0.003270 -0.010007 -0.007677 0.318655 10.119746\n13793 54.238370 -0.004001 -0.002603 -0.010078 -0.005341 0.293651 10.088881\n13794 54.244502 -0.003923 -0.002408 -0.009898 -0.000835 0.300957 10.082793\n13795 54.250492 -0.003936 -0.002633 -0.010151 0.010459 0.325807 10.113208\n13796 54.256507 -0.003961 -0.003014 -0.010456 0.014290 0.318503 10.123890\n13797 54.262666 -0.004164 -0.002942 -0.010431 0.011653 0.296630 10.113545\n13798 54.268476 -0.004235 -0.002660 -0.010495 0.006564 0.302415 10.102279\n13799 54.274827 -0.004493 -0.002425 -0.010751 -0.004011 0.330097 10.104631\n13800 54.280577 -0.004136 -0.002434 -0.011032 -0.002358 0.320705 10.112152\n13801 54.286661 -0.004049 -0.001884 -0.010516 0.013152 0.302653 10.096368\n13802 54.292633 -0.004399 -0.001804 -0.010093 0.019326 0.309321 10.096563\n13803 54.298656 -0.004115 -0.002554 -0.009074 0.008321 0.311674 10.101812\n13804 54.304935 -0.003674 -0.002620 -0.009060 0.010481 0.301845 10.094618\n13805 54.310925 -0.003913 -0.002742 -0.009376 0.009010 0.304453 10.083733\n13806 54.317060 -0.004090 -0.002458 -0.009490 0.001535 0.317549 10.090432\n13807 54.322940 -0.004164 -0.002271 -0.010162 0.015616 0.321325 10.128335\n13808 54.329154 -0.004290 -0.002150 -0.010425 0.017188 0.306806 10.135817\n13809 54.335098 -0.004736 -0.001675 -0.009968 0.010888 0.301231 10.097239\n13810 54.341120 -0.004643 -0.001746 -0.009969 0.011739 0.307733 10.080060\n13811 54.347075 -0.004624 -0.001562 -0.010320 0.018001 0.287711 10.087045\n13812 54.353264 -0.004649 -0.001616 -0.010478 0.017498 0.282633 10.096759\n13813 54.359427 -0.004901 -0.002258 -0.010088 0.012453 0.310708 10.113800\n13814 54.365289 -0.004503 -0.002374 -0.009810 0.013060 0.324697 10.122108\n13815 54.371243 -0.003508 -0.002562 -0.010028 0.010331 0.311989 10.114730\n13816 54.377331 -0.003379 -0.002540 -0.010193 0.004993 0.298174 10.111022\n13817 54.383414 -0.003782 -0.002478 -0.010256 0.006666 0.306588 10.106900\n13818 54.389404 -0.003454 -0.002390 -0.009946 0.009959 0.314645 10.108690\n13819 54.395568 -0.002997 -0.002551 -0.009010 0.013715 0.306157 10.086379\n13820 54.401538 -0.003270 -0.002796 -0.009034 0.016745 0.298082 10.072266\n13821 54.407527 -0.003666 -0.003192 -0.009308 0.010997 0.313803 10.088969\n13822 54.413528 -0.003533 -0.002720 -0.009456 0.009995 0.319885 10.097717\n13823 54.419646 -0.004029 -0.001730 -0.010514 0.016546 0.303929 10.092629\n13824 54.426297 -0.004762 -0.001227 -0.010790 0.019173 0.320145 10.067940\n13825 54.431680 -0.004510 -0.001336 -0.010584 0.021587 0.326382 10.075418\n13826 54.438107 -0.003917 -0.001705 -0.010425 0.022386 0.313315 10.083128\n13827 54.443659 -0.003939 -0.002080 -0.010032 0.015444 0.290505 10.085206\n13828 54.450299 -0.004202 -0.002703 -0.010119 -0.005443 0.315272 10.093323\n13829 54.455939 -0.003898 -0.002936 -0.010188 -0.010787 0.323502 10.105065\n13830 54.462175 -0.003735 -0.002801 -0.010375 -0.011444 0.307191 10.096456\n13831 54.467826 -0.004060 -0.002418 -0.010245 -0.012054 0.290847 10.079951\n13832 54.474372 -0.004275 -0.001966 -0.009716 -0.004139 0.308549 10.095137\n13833 54.479994 -0.004158 -0.001920 -0.009570 0.006974 0.319463 10.112102\n13834 54.486648 -0.003718 -0.002447 -0.010028 0.016150 0.302650 10.107754\n13835 54.492261 -0.003779 -0.003239 -0.010254 0.017719 0.296167 10.105425\n13836 54.498414 -0.003741 -0.004092 -0.010016 0.003850 0.329974 10.108409\n13837 54.504224 -0.003578 -0.003657 -0.009970 -0.000465 0.328982 10.111655\n13838 54.510445 -0.003371 -0.002344 -0.010362 0.004479 0.295955 10.107862\n13839 54.516250 -0.003901 -0.001930 -0.010507 0.009280 0.301352 10.096026\n13840 54.522372 -0.004338 -0.001338 -0.010694 0.002695 0.316089 10.092765\n13841 54.528419 -0.004234 -0.001338 -0.010791 -0.006362 0.318511 10.095544\n13842 54.534376 -0.003636 -0.002501 -0.010282 -0.008829 0.315292 10.099821\n13843 54.540335 -0.003874 -0.002840 -0.010258 -0.000125 0.318841 10.103653\n13844 54.546369 -0.003839 -0.003026 -0.010400 -0.000499 0.332699 10.114940\n13845 54.552263 -0.003432 -0.002956 -0.010131 -0.004813 0.322589 10.113545\n13846 54.558688 -0.003644 -0.002567 -0.010295 -0.003888 0.303040 10.097998\n13847 54.564564 -0.004021 -0.002418 -0.010228 0.002410 0.309345 10.098983\n13848 54.570802 -0.003622 -0.002575 -0.010274 0.009205 0.332539 10.110235\n13849 54.576592 -0.003360 -0.002548 -0.010215 0.018011 0.319695 10.113340\n13850 54.582814 -0.003879 -0.002657 -0.009567 0.029982 0.304793 10.111384\n13851 54.588619 -0.003883 -0.003168 -0.009606 0.024911 0.319067 10.110357\n13852 54.594805 -0.003590 -0.003496 -0.009868 0.006896 0.310841 10.109299\n13853 54.600738 -0.003636 -0.002691 -0.009792 0.007095 0.293344 10.099232\n13854 54.606900 -0.003981 -0.001891 -0.010160 0.016800 0.294441 10.085694\n13855 54.612862 -0.004194 -0.002178 -0.010387 0.019372 0.301644 10.088320\n13856 54.618852 -0.004102 -0.002297 -0.010005 0.021447 0.284159 10.126680\n13857 54.625060 -0.004252 -0.002171 -0.009751 0.015532 0.273290 10.123256\n13858 54.630908 -0.004137 -0.002552 -0.009783 -0.004990 0.305272 10.120128\n13859 54.637028 -0.004048 -0.002077 -0.009688 -0.006600 0.328092 10.126562\n13860 54.642942 -0.003451 -0.001255 -0.009718 -0.013402 0.311911 10.105685\n13861 54.649123 -0.003269 -0.001265 -0.010051 -0.014380 0.295313 10.085432\n13862 54.655238 -0.004241 -0.002102 -0.010520 -0.014132 0.313414 10.081616\n13863 54.661193 -0.004634 -0.002313 -0.010358 -0.005325 0.321395 10.091146\n13864 54.667445 -0.004724 -0.002576 -0.009830 0.017300 0.301902 10.105904\n13865 54.673229 -0.004542 -0.002743 -0.009799 0.023424 0.293679 10.093533\n13866 54.679530 -0.004060 -0.002718 -0.010024 0.017317 0.319232 10.090506\n13867 54.685392 -0.003686 -0.002721 -0.009876 0.006997 0.321101 10.100664\n13868 54.691500 -0.003535 -0.001818 -0.009629 0.009385 0.288612 10.100080\n13869 54.697636 -0.003776 -0.001713 -0.009870 0.008970 0.293244 10.094520\n13870 54.703488 -0.004052 -0.001823 -0.010401 0.003227 0.318445 10.090788\n13871 54.709478 -0.004052 -0.002068 -0.010406 -0.003502 0.310171 10.095022\n13872 54.715537 -0.003794 -0.002899 -0.010456 -0.004082 0.286878 10.089240\n13873 54.721643 -0.003694 -0.003010 -0.010513 -0.000369 0.297571 10.087941\n13874 54.727757 -0.003628 -0.002663 -0.010520 0.008694 0.319017 10.107174\n13875 54.733827 -0.003411 -0.002196 -0.010608 0.012610 0.309668 10.100459\n13876 54.739645 -0.004094 -0.001761 -0.010500 0.020958 0.291659 10.081364\n13877 54.745677 -0.004231 -0.001581 -0.010379 0.026033 0.295329 10.075572\n13878 54.751773 -0.003855 -0.001962 -0.009815 0.018322 0.315339 10.081040\n13879 54.758104 -0.003871 -0.002176 -0.009866 0.014047 0.309494 10.087883\n13880 54.763887 -0.004642 -0.002278 -0.010310 0.022353 0.294187 10.096827\n13881 54.769917 -0.004665 -0.002917 -0.010181 0.025010 0.308067 10.107075\n13882 54.776048 -0.004212 -0.003653 -0.010224 0.021422 0.335684 10.125271\n13883 54.781923 -0.004061 -0.003249 -0.010615 0.015739 0.328760 10.123816\n13884 54.788202 -0.004351 -0.002359 -0.010648 0.011453 0.326994 10.111437\n13885 54.794151 -0.004214 -0.002265 -0.010422 0.014827 0.329273 10.112463\n13886 54.800236 -0.003726 -0.002062 -0.010315 0.023589 0.323621 10.129436\n13887 54.806178 -0.003731 -0.002003 -0.010115 0.025896 0.300822 10.110844\n13888 54.812195 -0.004316 -0.002609 -0.009878 0.018980 0.293849 10.082293\n13889 54.818818 -0.004296 -0.003081 -0.010209 0.009780 0.320721 10.080937\n13890 54.824348 -0.004145 -0.003150 -0.010429 0.009485 0.309756 10.081719\n13891 54.830723 -0.003982 -0.002673 -0.010621 0.002724 0.284016 10.073847\n13892 54.836371 -0.004004 -0.002619 -0.010627 0.003539 0.300050 10.086800\n13893 54.842799 -0.004341 -0.001812 -0.009994 0.018603 0.313911 10.120514\n13894 54.848447 -0.004380 -0.001468 -0.009799 0.014177 0.295421 10.120125\n13895 54.854757 -0.004781 -0.001875 -0.010231 0.004018 0.283212 10.090246\n13896 54.860475 -0.004794 -0.002092 -0.010195 0.008612 0.295662 10.088700\n13897 54.866968 -0.004691 -0.002028 -0.009970 0.003515 0.314113 10.085052\n13898 54.872594 -0.004396 -0.001748 -0.009975 0.001227 0.309160 10.077634\n13899 54.878988 -0.004355 -0.002106 -0.010338 0.000897 0.313673 10.085136\n13900 54.884687 -0.004191 -0.002686 -0.010504 0.008323 0.327946 10.084899\n13901 54.891165 -0.003856 -0.002841 -0.010289 0.030517 0.326458 10.093832\n13902 54.896714 -0.004087 -0.002952 -0.009944 0.034897 0.305619 10.082465\n13903 54.902892 -0.004361 -0.002764 -0.009975 0.021445 0.310042 10.075484\n13904 54.908944 -0.004317 -0.002963 -0.009893 0.011571 0.328987 10.089421\n13905 54.914972 -0.004376 -0.002984 -0.010147 0.018067 0.323193 10.113319\n13906 54.920952 -0.004375 -0.002615 -0.010462 0.021251 0.312664 10.120692\n13907 54.926961 -0.004045 -0.002033 -0.010748 0.012640 0.312689 10.118460\n13908 54.933022 -0.004047 -0.002017 -0.010466 0.014646 0.306328 10.121556\n13909 54.939261 -0.004490 -0.002467 -0.009646 0.002186 0.289705 10.102257\n13910 54.944995 -0.004755 -0.002361 -0.009511 -0.001271 0.293812 10.096985\n13911 54.951294 -0.004940 -0.002058 -0.009704 -0.005012 0.324769 10.094590\n13912 54.957239 -0.004763 -0.001803 -0.009896 -0.004049 0.327931 10.093185\n13913 54.963313 -0.004347 -0.001615 -0.010377 0.010706 0.303161 10.087938\n13914 54.969141 -0.004153 -0.001727 -0.010659 0.012302 0.302278 10.090931\n13915 54.975321 -0.004555 -0.002247 -0.010700 0.013358 0.324260 10.106355\n13916 54.981204 -0.004456 -0.002656 -0.010627 0.019719 0.316437 10.106772\n13917 54.987421 -0.004406 -0.003214 -0.010005 0.029026 0.303107 10.090882\n13918 54.993312 -0.004598 -0.003360 -0.009890 0.021840 0.314174 10.082662\n13919 54.999601 -0.004874 -0.003182 -0.010297 0.003997 0.329367 10.086207\n13920 55.005442 -0.004746 -0.002816 -0.010539 -0.000563 0.320788 10.089032\n13921 55.011540 -0.004522 -0.002169 -0.010948 0.004662 0.291896 10.094197\n13922 55.017454 -0.004739 -0.002025 -0.010917 0.004132 0.303538 10.094281\n13923 55.023611 -0.004902 -0.001757 -0.010424 0.003082 0.314106 10.119893\n13924 55.029643 -0.004329 -0.001986 -0.010008 0.001892 0.300129 10.117146\n13925 55.035688 -0.004375 -0.003516 -0.009541 -0.002012 0.313466 10.107105\n13926 55.041552 -0.004313 -0.003806 -0.009870 -0.007217 0.341024 10.109316\n13927 55.047688 -0.004071 -0.002872 -0.010467 -0.009142 0.331774 10.136523\n13928 55.053764 -0.004170 -0.002151 -0.010438 -0.006415 0.317017 10.148399\n13929 55.059862 -0.004542 -0.001672 -0.010233 0.002190 0.326487 10.137374\n13930 55.065904 -0.004578 -0.001619 -0.010212 0.006088 0.330526 10.131542\n13931 55.071864 -0.004224 -0.001745 -0.010574 0.019839 0.327608 10.102075\n13932 55.078060 -0.004242 -0.002279 -0.010506 0.026317 0.318566 10.080021\n13933 55.084025 -0.004252 -0.002707 -0.010223 0.008690 0.313686 10.055529\n13934 55.090080 -0.003891 -0.002767 -0.010051 -0.006452 0.322162 10.068252\n13935 55.095977 -0.003467 -0.002668 -0.010248 -0.003587 0.323312 10.091296\n13936 55.102036 -0.003568 -0.002190 -0.010356 0.009851 0.319262 10.093564\n13937 55.108209 -0.004273 -0.002751 -0.010468 0.019902 0.321046 10.097298\n13938 55.114307 -0.004337 -0.002875 -0.010301 0.017285 0.314877 10.096094\n13939 55.120422 -0.004087 -0.002555 -0.010189 0.003375 0.282583 10.089725\n13940 55.126175 -0.003936 -0.002422 -0.009930 -0.001927 0.272125 10.088891\n13941 55.132397 -0.004004 -0.002570 -0.010101 0.003628 0.305605 10.108733\n13942 55.138272 -0.003844 -0.002916 -0.010044 0.007917 0.330214 10.121181\n13943 55.144234 -0.003522 -0.002582 -0.010384 0.006951 0.327420 10.123377\n13944 55.150520 -0.003421 -0.002381 -0.010517 0.000824 0.323896 10.105390\n13945 55.156458 -0.003747 -0.002283 -0.010184 0.002388 0.335018 10.090107\n13946 55.162541 -0.003654 -0.002423 -0.010270 0.011963 0.323833 10.099655\n13947 55.168437 -0.004135 -0.002719 -0.010085 0.025906 0.300674 10.109021\n13948 55.174424 -0.004279 -0.003025 -0.009936 0.033071 0.298377 10.113276\n13949 55.180585 -0.004069 -0.003309 -0.009029 0.040736 0.309937 10.139333\n13950 55.186520 -0.003607 -0.003274 -0.009025 0.032134 0.313907 10.141328\n13951 55.192651 -0.003759 -0.002495 -0.009882 0.014808 0.308071 10.115219\n13952 55.198721 -0.003925 -0.002144 -0.010116 0.016081 0.313630 10.110985\n13953 55.204583 -0.003966 -0.002150 -0.010413 0.019336 0.319797 10.111057\n13954 55.210698 -0.004028 -0.002226 -0.010935 0.020918 0.300843 10.103146\n13955 55.216808 -0.004656 -0.002583 -0.011253 0.022639 0.278490 10.091300\n13956 55.222931 -0.004742 -0.002578 -0.010661 0.018309 0.293324 10.078879\n13957 55.228924 -0.004577 -0.002514 -0.009693 0.004490 0.320512 10.071478\n13958 55.234870 -0.004241 -0.002800 -0.009554 0.007612 0.316104 10.071767\n13959 55.241169 -0.003937 -0.002952 -0.010121 0.011353 0.317770 10.071754\n13960 55.247279 -0.004472 -0.002644 -0.010117 0.011384 0.324968 10.070724\n13961 55.253195 -0.004629 -0.002334 -0.009939 0.022333 0.315526 10.073351\n13962 55.259098 -0.004396 -0.002676 -0.009501 0.025830 0.302983 10.073580\n13963 55.265310 -0.004297 -0.003292 -0.009184 0.027991 0.304634 10.077560\n13964 55.271732 -0.004008 -0.003277 -0.009432 0.008899 0.320379 10.096973\n13965 55.277207 -0.003523 -0.003039 -0.009557 0.004035 0.312562 10.101028\n13966 55.283742 -0.003466 -0.001780 -0.010670 0.001744 0.295272 10.101235\n13967 55.289523 -0.004048 -0.001400 -0.010864 -0.002287 0.302081 10.104224\n13968 55.295814 -0.004252 -0.000915 -0.010571 0.009980 0.305978 10.117208\n13969 55.301500 -0.003950 -0.000961 -0.010135 0.016067 0.290850 10.122226\n13970 55.307848 -0.003965 -0.001496 -0.009122 0.014551 0.286077 10.110867\n13971 55.313522 -0.003799 -0.002192 -0.008759 0.006462 0.307517 10.111457\n13972 55.319788 -0.003483 -0.002409 -0.009062 -0.004530 0.333874 10.111778\n13973 55.325500 -0.003732 -0.002112 -0.009666 -0.002873 0.324223 10.110850\n13974 55.331976 -0.004125 -0.001310 -0.010504 0.016676 0.307359 10.092949\n13975 55.337574 -0.003796 -0.001203 -0.010765 0.017711 0.309724 10.096020\n13976 55.343822 -0.003501 -0.001426 -0.010313 0.014683 0.290348 10.105233\n13977 55.349614 -0.003691 -0.002187 -0.009921 0.016615 0.287116 10.097185\n13978 55.355772 -0.003685 -0.003373 -0.009636 0.018791 0.308085 10.089550\n13979 55.361798 -0.003670 -0.003392 -0.009935 0.020645 0.320248 10.098802\n13980 55.367797 -0.003918 -0.003113 -0.010492 0.025002 0.313369 10.102914\n13981 55.373956 -0.003990 -0.002567 -0.010603 0.024111 0.309217 10.094219\n13982 55.379787 -0.003747 -0.002301 -0.010654 0.026927 0.321276 10.099773\n13983 55.385822 -0.003766 -0.002500 -0.010710 0.023904 0.327299 10.103180\n13984 55.391941 -0.003752 -0.002697 -0.009972 0.021505 0.308221 10.080964\n13985 55.397958 -0.003965 -0.002514 -0.009698 0.024966 0.304002 10.063673\n13986 55.404063 -0.003989 -0.002446 -0.009844 0.020136 0.333543 10.065082\n13987 55.410030 -0.003580 -0.002588 -0.009913 0.013401 0.339440 10.082865\n13988 55.416273 -0.003284 -0.001934 -0.010261 0.005003 0.315721 10.106446\n13989 55.422434 -0.003834 -0.001404 -0.010420 0.004513 0.309675 10.101950\n13990 55.428295 -0.003884 -0.001141 -0.010941 0.002988 0.320024 10.113718\n13991 55.434249 -0.003757 -0.001791 -0.010853 0.006949 0.311614 10.117203\n13992 55.440401 -0.004342 -0.002840 -0.010201 0.012632 0.296338 10.094251\n13993 55.446233 -0.004561 -0.003042 -0.010044 0.011483 0.306186 10.080187\n13994 55.452366 -0.004572 -0.002646 -0.010283 0.010421 0.329293 10.087067\n13995 55.458355 -0.004592 -0.002537 -0.010396 0.006817 0.323044 10.076738\n13996 55.464372 -0.004162 -0.002516 -0.010914 0.001372 0.309989 10.077096\n13997 55.470473 -0.004016 -0.002467 -0.011032 0.001200 0.311440 10.095010\n13998 55.476525 -0.003695 -0.002379 -0.011276 -0.001244 0.320064 10.113600\n13999 55.482579 -0.003371 -0.002471 -0.010921 0.009744 0.312844 10.105682\n14000 55.488597 -0.003633 -0.002902 -0.010376 0.018192 0.317499 10.077648\n14001 55.494646 -0.003926 -0.003079 -0.010094 0.013556 0.334934 10.072656\n14002 55.500611 -0.003931 -0.002998 -0.010150 0.000262 0.331740 10.092588\n14003 55.506575 -0.003520 -0.003025 -0.010370 -0.008918 0.314760 10.103382\n14004 55.512593 -0.003394 -0.002140 -0.010457 -0.006981 0.308413 10.103005\n14005 55.518648 -0.003868 -0.001791 -0.010543 0.000804 0.312547 10.089064\n14006 55.524697 -0.004396 -0.001575 -0.010426 0.015957 0.312650 10.091469\n14007 55.530849 -0.004492 -0.001855 -0.010221 0.018240 0.305578 10.096164\n14008 55.536867 -0.004742 -0.002410 -0.009789 0.007105 0.321388 10.086887\n14009 55.542894 -0.004595 -0.002541 -0.009664 -0.000440 0.330488 10.081734\n14010 55.548985 -0.004765 -0.002534 -0.010034 0.003895 0.315504 10.086203\n14011 55.555105 -0.004888 -0.002564 -0.010416 0.004831 0.298782 10.088679\n14012 55.560949 -0.003897 -0.002405 -0.010919 0.007427 0.308069 10.095671\n14013 55.567205 -0.003422 -0.002147 -0.010765 0.012377 0.313651 10.099075\n14014 55.573227 -0.003191 -0.002297 -0.010419 0.016435 0.299329 10.099500\n14015 55.579257 -0.003569 -0.002733 -0.010424 0.020875 0.298221 10.104654\n14016 55.585231 -0.004304 -0.002593 -0.010036 0.016105 0.329923 10.113126\n14017 55.591268 -0.004319 -0.002722 -0.009932 0.012743 0.335947 10.110121\n14018 55.597253 -0.004577 -0.002321 -0.009618 0.009753 0.312972 10.105164\n14019 55.603354 -0.004863 -0.002192 -0.009702 0.005917 0.308724 10.100483\n14020 55.609145 -0.004909 -0.002196 -0.010751 0.007978 0.305753 10.102319\n14021 55.615298 -0.004637 -0.001931 -0.010907 0.002583 0.300209 10.104446\n14022 55.621327 -0.004762 -0.001663 -0.010485 0.001652 0.296692 10.094112\n14023 55.627480 -0.004899 -0.002538 -0.010047 0.006826 0.310510 10.091348\n14024 55.633433 -0.004506 -0.003803 -0.009571 -0.000370 0.334596 10.095126\n14025 55.639749 -0.003985 -0.003770 -0.009756 -0.007230 0.324588 10.104455\n14026 55.645487 -0.003541 -0.002581 -0.010391 -0.003746 0.306506 10.103712\n14027 55.651455 -0.003742 -0.002212 -0.010652 -0.005542 0.307395 10.105285\n14028 55.657583 -0.003981 -0.001637 -0.010958 -0.004837 0.315899 10.101367\n14029 55.663716 -0.004007 -0.001576 -0.010595 0.010080 0.309236 10.084206\n14030 55.669846 -0.004079 -0.002509 -0.009331 0.029432 0.306656 10.080180\n14031 55.675762 -0.004565 -0.003019 -0.009126 0.029928 0.319628 10.091296\n14032 55.681824 -0.004370 -0.003208 -0.009287 0.022103 0.321681 10.101578\n14033 55.687781 -0.004203 -0.002967 -0.009477 0.022370 0.317209 10.092288\n14034 55.693983 -0.004748 -0.002411 -0.010318 0.028698 0.320442 10.091546\n14035 55.699898 -0.004551 -0.002095 -0.010663 0.027161 0.328686 10.091304\n14036 55.705859 -0.003835 -0.001809 -0.010740 0.019275 0.315200 10.084819\n14037 55.711903 -0.003685 -0.002377 -0.010693 0.015786 0.306324 10.087883\n14038 55.717889 -0.003994 -0.003301 -0.010538 0.013212 0.328403 10.109272\n14039 55.724748 -0.003454 -0.003546 -0.010308 0.016703 0.332892 10.127563\n14040 55.730156 -0.003440 -0.003047 -0.010144 0.016571 0.320248 10.124677\n14041 55.736558 -0.004139 -0.001691 -0.010524 0.015941 0.318208 10.120376\n14042 55.742742 -0.004268 -0.001352 -0.010418 0.012959 0.322161 10.127307\n14043 55.748767 -0.003461 -0.001878 -0.010320 0.007225 0.315996 10.127935\n14044 55.754247 -0.003476 -0.002516 -0.010272 0.008266 0.307817 10.122805\n14045 55.760694 -0.003739 -0.003340 -0.009774 0.001646 0.318919 10.120681\n14046 55.766351 -0.003518 -0.003636 -0.009623 -0.001336 0.327109 10.121507\n14047 55.772638 -0.003164 -0.003268 -0.010051 0.004562 0.307237 10.115294\n14048 55.778360 -0.003577 -0.002698 -0.010344 0.012045 0.296782 10.105398\n14049 55.784846 -0.004462 -0.002049 -0.010616 0.016939 0.321470 10.105130\n14050 55.790532 -0.004318 -0.001752 -0.010715 0.006779 0.324814 10.108379\n14051 55.796840 -0.004016 -0.002000 -0.010675 0.003502 0.299679 10.094023\n14052 55.802609 -0.004163 -0.002213 -0.010626 0.014161 0.293821 10.075851\n14053 55.808687 -0.003840 -0.003089 -0.010330 0.007805 0.312997 10.069276\n14054 55.814803 -0.003857 -0.003362 -0.010140 0.005302 0.317418 10.076385\n14055 55.821010 -0.003952 -0.003212 -0.010023 0.011293 0.315863 10.085312\n14056 55.826778 -0.004190 -0.003011 -0.010497 0.018067 0.322207 10.076819\n14057 55.833003 -0.004453 -0.002608 -0.011328 0.011154 0.337285 10.083938\n14058 55.838812 -0.004678 -0.002475 -0.011308 0.009928 0.326197 10.081404\n14059 55.845223 -0.004789 -0.002021 -0.010414 0.012738 0.290045 10.080190\n14060 55.850760 -0.004870 -0.002194 -0.009969 0.001222 0.295372 10.080398\n14061 55.856966 -0.004840 -0.003093 -0.009523 0.008422 0.317690 10.089336\n14062 55.862853 -0.004384 -0.003104 -0.009520 0.011205 0.313715 10.099232\n14063 55.869127 -0.004341 -0.002052 -0.010346 0.000502 0.315789 10.094047\n14064 55.874949 -0.004486 -0.001665 -0.010902 0.001166 0.331039 10.094543\n14065 55.881132 -0.003599 -0.001355 -0.011052 0.015491 0.336154 10.102614\n14066 55.887104 -0.003184 -0.001659 -0.010705 0.017619 0.320440 10.101211\n14067 55.893249 -0.003712 -0.002837 -0.009936 0.033216 0.305333 10.092813\n14068 55.899226 -0.004238 -0.003470 -0.009764 0.030583 0.309673 10.100951\n14069 55.905182 -0.004043 -0.003730 -0.009132 0.006756 0.315876 10.096244\n14070 55.911394 -0.003859 -0.003306 -0.008867 -0.004389 0.314800 10.077470\n14071 55.917395 -0.004695 -0.002334 -0.009467 -0.018686 0.322067 10.069427\n14072 55.923429 -0.004831 -0.002072 -0.010131 -0.006292 0.322568 10.086709\n14073 55.929354 -0.004649 -0.001894 -0.010531 0.033465 0.308645 10.084931\n14074 55.935437 -0.004780 -0.002030 -0.010522 0.033307 0.295225 10.071724\n14075 55.941392 -0.004563 -0.002761 -0.009970 0.017224 0.305143 10.070243\n14076 55.947830 -0.004586 -0.002994 -0.009717 0.015702 0.328001 10.070935\n14077 55.953579 -0.004160 -0.002656 -0.009644 0.016354 0.326912 10.107975\n14078 55.959573 -0.003807 -0.002513 -0.009814 0.017544 0.320362 10.123940\n14079 55.965711 -0.004273 -0.003063 -0.010614 0.009917 0.330077 10.108795\n14080 55.971640 -0.004362 -0.002681 -0.010822 0.012718 0.325717 10.108784\n14081 55.977651 -0.004125 -0.002166 -0.010574 0.010404 0.294520 10.117296\n14082 55.983591 -0.004413 -0.002298 -0.010141 0.019157 0.289233 10.103731\n14083 55.989879 -0.004684 -0.003408 -0.009673 0.031665 0.310556 10.098304\n14084 55.995902 -0.004463 -0.003556 -0.009687 0.029256 0.319728 10.104456\n14085 56.001858 -0.003835 -0.002850 -0.010048 0.011943 0.315959 10.089075\n14086 56.008008 -0.004080 -0.002443 -0.010140 0.000908 0.315356 10.090470\n14087 56.014029 -0.004347 -0.002057 -0.010515 -0.011256 0.341445 10.094596\n14088 56.020007 -0.003912 -0.001720 -0.010912 -0.009823 0.339285 10.098700\n14089 56.026134 -0.003447 -0.001427 -0.011174 0.005027 0.291672 10.114008\n14090 56.032162 -0.003964 -0.002008 -0.010815 0.006951 0.285310 10.110970\n14091 56.038134 -0.004790 -0.003148 -0.010288 0.013802 0.306856 10.097089\n14092 56.044256 -0.004709 -0.003391 -0.009930 0.013081 0.304176 10.091402\n14093 56.050646 -0.004221 -0.002837 -0.009540 -0.002357 0.299651 10.096529\n14094 56.056384 -0.004271 -0.002028 -0.009481 -0.005553 0.314794 10.092369\n14095 56.062260 -0.004317 -0.001148 -0.009522 -0.005608 0.325682 10.077124\n14096 56.068217 -0.004208 -0.000647 -0.009835 -0.006878 0.312284 10.083367\n14097 56.074310 -0.003924 -0.000116 -0.010272 -0.006214 0.306091 10.080438\n14098 56.080345 -0.003816 -0.000663 -0.010065 -0.010812 0.312556 10.087339\n14099 56.086691 -0.003460 -0.003021 -0.009919 -0.008017 0.319796 10.117002\n14100 56.092523 -0.003309 -0.003225 -0.009757 0.001169 0.314014 10.112531\n14101 56.098519 -0.004043 -0.002965 -0.010202 0.004967 0.321018 10.085684\n14102 56.104638 -0.004228 -0.002687 -0.010357 -0.000620 0.334374 10.081074\n14103 56.110640 -0.004218 -0.002957 -0.010214 0.002312 0.328325 10.094031\n14104 56.116648 -0.004183 -0.002866 -0.010242 0.012514 0.311177 10.102110\n14105 56.122888 -0.004019 -0.002303 -0.010244 0.025755 0.293567 10.111851\n14106 56.128765 -0.003913 -0.002290 -0.010220 0.026724 0.297540 10.123693\n14107 56.134711 -0.003643 -0.002421 -0.009422 0.018618 0.302692 10.120935\n14108 56.140683 -0.003854 -0.002486 -0.009239 0.012524 0.299567 10.104371\n14109 56.146819 -0.004370 -0.002494 -0.009567 -0.005296 0.314481 10.097903\n14110 56.153976 -0.004408 -0.002522 -0.010007 -0.005595 0.324483 10.118066\n14111 56.160896 -0.004378 -0.002372 -0.009987 0.001557 0.306467 10.120698\n14112 56.166010 -0.004582 -0.002563 -0.009767 0.019907 0.302951 10.110107\n14113 56.171938 -0.004983 -0.002784 -0.009832 0.027563 0.327067 10.101843\n14114 56.178064 -0.005145 -0.002913 -0.010135 0.022902 0.351243 10.111899\n14115 56.184063 -0.004848 -0.002700 -0.010091 0.016463 0.332066 10.102101\n14116 56.190072 -0.004817 -0.001881 -0.009782 0.001252 0.309824 10.074039\n14117 56.196127 -0.004599 -0.001667 -0.009943 -0.001151 0.321857 10.083281\n14118 56.202196 -0.003647 -0.001438 -0.010441 0.008204 0.328654 10.104656\n14119 56.208249 -0.003652 -0.001705 -0.010475 0.011924 0.319402 10.108183\n14120 56.214304 -0.004096 -0.002501 -0.010310 0.016414 0.319907 10.100275\n14121 56.220456 -0.004166 -0.002987 -0.010220 0.016587 0.324694 10.101068\n14122 56.226257 -0.004003 -0.003289 -0.009843 0.022755 0.314901 10.106429\n14123 56.232434 -0.004005 -0.003006 -0.009908 0.017775 0.307549 10.101084\n14124 56.238460 -0.003985 -0.002188 -0.009954 0.004965 0.327483 10.100437\n14125 56.244418 -0.003614 -0.002164 -0.009808 -0.000448 0.340100 10.090940\n14126 56.250639 -0.003389 -0.002348 -0.009833 0.000068 0.317538 10.088593\n14127 56.256560 -0.003882 -0.002206 -0.009968 0.001673 0.308261 10.076506\n14128 56.262731 -0.004585 -0.002245 -0.010242 0.012556 0.320810 10.071671\n14129 56.268625 -0.004516 -0.002660 -0.010277 0.015501 0.331108 10.088065\n14130 56.274615 -0.004310 -0.002707 -0.009872 0.018053 0.319789 10.108343\n14131 56.280640 -0.004273 -0.002146 -0.009666 0.015168 0.320802 10.102979\n14132 56.286798 -0.004717 -0.001461 -0.009661 0.008604 0.348529 10.092045\n14133 56.292824 -0.004256 -0.001501 -0.009638 0.004139 0.342442 10.099363\n14134 56.298760 -0.003824 -0.001751 -0.010154 0.012298 0.302949 10.104548\n14135 56.304870 -0.004300 -0.002281 -0.010451 0.022469 0.299586 10.103282\n14136 56.310995 -0.004536 -0.002600 -0.010128 0.021997 0.325709 10.107599\n14137 56.316936 -0.004077 -0.002839 -0.009833 0.013730 0.319710 10.109342\n14138 56.322973 -0.003744 -0.003026 -0.009843 -0.002360 0.303644 10.094152\n14139 56.329143 -0.004048 -0.002911 -0.009921 -0.014089 0.316593 10.089757\n14140 56.335350 -0.004386 -0.002658 -0.010559 -0.007775 0.339160 10.102216\n14141 56.341223 -0.004157 -0.002457 -0.010715 0.000566 0.328738 10.116309\n14142 56.347325 -0.004286 -0.002468 -0.010688 0.012885 0.292337 10.143949\n14143 56.353874 -0.004461 -0.003115 -0.010619 0.009773 0.316617 10.126255\n14144 56.359373 -0.003809 -0.003600 -0.010366 0.005965 0.323086 10.119690\n14145 56.365678 -0.003439 -0.003067 -0.009690 0.004777 0.309837 10.092078\n14146 56.371462 -0.003518 -0.002759 -0.009450 -0.001037 0.313578 10.088032\n14147 56.377800 -0.003520 -0.001724 -0.009974 -0.003565 0.338665 10.103734\n14148 56.383435 -0.003589 -0.001565 -0.010323 -0.004273 0.331631 10.112203\n14149 56.389779 -0.003479 -0.001868 -0.010947 -0.001951 0.307697 10.107083\n14150 56.395404 -0.003754 -0.002192 -0.010626 -0.008176 0.311710 10.096428\n14151 56.401880 -0.004479 -0.002948 -0.010055 -0.005094 0.325743 10.095320\n14152 56.407640 -0.004501 -0.002832 -0.009933 -0.000341 0.315330 10.097982\n14153 56.413982 -0.003995 -0.002435 -0.009617 0.008248 0.298627 10.082295\n14154 56.419536 -0.003829 -0.002348 -0.009584 0.004845 0.318671 10.081563\n14155 56.425972 -0.003792 -0.002478 -0.010363 -0.005050 0.339655 10.103936\n14156 56.431718 -0.003804 -0.002252 -0.010665 0.002820 0.302040 10.113177\n14157 56.438006 -0.004337 -0.002250 -0.010696 0.009034 0.281900 10.098999\n14158 56.443743 -0.004121 -0.002468 -0.010647 0.009514 0.309008 10.111650\n14159 56.449931 -0.003325 -0.002643 -0.010171 0.016429 0.328548 10.129364\n14160 56.455768 -0.003410 -0.002519 -0.010048 0.017937 0.317462 10.122215\n14161 56.462031 -0.004298 -0.001774 -0.010376 0.009736 0.306165 10.095321\n14162 56.467955 -0.004675 -0.001751 -0.010789 -0.003900 0.323676 10.094880\n14163 56.474142 -0.004396 -0.002118 -0.010746 0.002160 0.319596 10.122050\n14164 56.480282 -0.004267 -0.002263 -0.010263 0.013786 0.301088 10.129532\n14165 56.486272 -0.004562 -0.002734 -0.009639 0.013593 0.302149 10.126203\n14166 56.492297 -0.004571 -0.002861 -0.009601 0.007572 0.315462 10.120498\n14167 56.498271 -0.004514 -0.003177 -0.009547 0.010685 0.299415 10.096020\n14168 56.504297 -0.004693 -0.003034 -0.009626 0.009345 0.291955 10.086825\n14169 56.510307 -0.004834 -0.002967 -0.009859 -0.009731 0.335877 10.103495\n14170 56.516415 -0.004421 -0.002675 -0.010433 -0.002790 0.354969 10.127261\n14171 56.522424 -0.004449 -0.001767 -0.010812 0.005951 0.317685 10.121314\n14172 56.528432 -0.004987 -0.001835 -0.010570 0.009996 0.299899 10.105100\n14173 56.534581 -0.005140 -0.002772 -0.010687 0.008201 0.303738 10.095268\n14174 56.540469 -0.005091 -0.002800 -0.010683 0.008776 0.309690 10.101921\n14175 56.546520 -0.004434 -0.003125 -0.010382 0.019345 0.300075 10.121167\n14176 56.552638 -0.004268 -0.002883 -0.010089 0.020986 0.302280 10.127810\n14177 56.558657 -0.004767 -0.002472 -0.010306 0.007046 0.337876 10.135185\n14178 56.564516 -0.004621 -0.002313 -0.010460 0.004592 0.337431 10.132727\n14179 56.570743 -0.004401 -0.002014 -0.010857 0.013113 0.283731 10.122666\n14180 56.576557 -0.004598 -0.002466 -0.011090 0.019263 0.286405 10.120059\n14181 56.582680 -0.004378 -0.003562 -0.010248 0.021141 0.323418 10.129455\n14182 56.588785 -0.003818 -0.003673 -0.009719 0.014552 0.324541 10.133534\n14183 56.594893 -0.003915 -0.003627 -0.009705 0.003923 0.309038 10.103169\n14184 56.600729 -0.004290 -0.003261 -0.010312 -0.000474 0.322724 10.098722\n14185 56.606770 -0.004280 -0.001935 -0.011293 0.002647 0.328165 10.117718\n14186 56.612759 -0.004245 -0.001792 -0.011250 0.010692 0.315068 10.120379\n14187 56.619214 -0.004939 -0.002103 -0.010956 0.021953 0.299693 10.096987\n14188 56.625135 -0.004993 -0.002242 -0.010748 0.021123 0.301537 10.085051\n14189 56.631152 -0.004187 -0.002453 -0.010071 0.014454 0.308493 10.092537\n14190 56.637065 -0.004088 -0.002634 -0.009482 0.016725 0.305298 10.090975\n14191 56.643091 -0.004529 -0.002938 -0.009470 0.018537 0.303775 10.078376\n14192 56.649233 -0.004548 -0.003011 -0.009482 0.014597 0.320369 10.081459\n14193 56.655251 -0.004195 -0.002240 -0.010201 0.017204 0.333563 10.095301\n14194 56.661673 -0.004158 -0.001767 -0.010620 0.021648 0.321976 10.094309\n14195 56.667382 -0.004456 -0.002535 -0.010581 0.022572 0.321454 10.100457\n14196 56.673422 -0.004080 -0.002791 -0.010079 0.020448 0.329399 10.112972\n14197 56.679390 -0.003554 -0.002577 -0.009721 0.011729 0.311255 10.114338\n14198 56.685467 -0.003454 -0.002446 -0.009726 0.005403 0.306337 10.101570\n14199 56.691554 -0.003276 -0.002336 -0.010306 0.002316 0.332323 10.090905\n14200 56.697512 -0.002720 -0.001925 -0.010683 0.009756 0.333978 10.090970\n14201 56.703514 -0.003425 -0.001182 -0.011291 0.014695 0.303633 10.090018\n14202 56.709596 -0.004584 -0.001236 -0.011061 0.015703 0.293332 10.092659\n14203 56.715850 -0.005525 -0.002122 -0.010419 0.022028 0.312912 10.107137\n14204 56.721673 -0.005087 -0.002297 -0.010129 0.021822 0.315273 10.114382\n14205 56.727687 -0.004348 -0.001964 -0.008966 0.012254 0.297482 10.121962\n14206 56.733676 -0.004295 -0.002159 -0.009019 0.013032 0.297093 10.118402\n14207 56.739847 -0.004257 -0.002400 -0.010239 0.011642 0.327513 10.121588\n14208 56.745883 -0.004038 -0.002479 -0.010303 0.015500 0.332675 10.114184\n14209 56.752111 -0.004086 -0.002424 -0.010443 0.017906 0.312362 10.093513\n14210 56.757889 -0.004577 -0.002386 -0.010473 0.019184 0.301615 10.088247\n14211 56.763982 -0.004894 -0.003027 -0.009737 0.010482 0.321531 10.097532\n14212 56.770026 -0.004585 -0.003634 -0.009564 0.007553 0.324518 10.099213\n14213 56.776010 -0.004334 -0.003665 -0.009490 0.001489 0.306012 10.093299\n14214 56.782809 -0.004169 -0.003524 -0.009507 -0.002583 0.311123 10.093275\n14215 56.788258 -0.003382 -0.002709 -0.009796 0.000554 0.326794 10.105333\n14216 56.794255 -0.003421 -0.002049 -0.010150 0.006696 0.319034 10.118211\n14217 56.800304 -0.003740 -0.001994 -0.010585 0.011570 0.301803 10.101348\n14218 56.806882 -0.004111 -0.002390 -0.010682 0.019418 0.299791 10.085143\n14219 56.812406 -0.004328 -0.002423 -0.009643 0.023432 0.305744 10.095155\n14220 56.819015 -0.004251 -0.002471 -0.009808 0.010915 0.311319 10.092214\n14221 56.824381 -0.004535 -0.002598 -0.010251 0.001580 0.322068 10.087737\n14222 56.830906 -0.004792 -0.002646 -0.011071 -0.008100 0.348388 10.094254\n14223 56.836529 -0.004487 -0.002410 -0.011426 -0.003991 0.339886 10.102680\n14224 56.843029 -0.004035 -0.001579 -0.011448 0.005598 0.292885 10.106838\n14225 56.848632 -0.003959 -0.001684 -0.011010 0.006854 0.295464 10.101490\n14226 56.854928 -0.002922 -0.002954 -0.010167 0.015824 0.333216 10.090233\n14227 56.860650 -0.002529 -0.003216 -0.009860 0.025568 0.328223 10.088613\n14228 56.867035 -0.003049 -0.002907 -0.010105 0.027249 0.301468 10.076197\n14229 56.872795 -0.003252 -0.002618 -0.010581 0.021328 0.305348 10.067393\n14230 56.879033 -0.004253 -0.002403 -0.010812 0.010966 0.322804 10.084642\n14231 56.885142 -0.004742 -0.002472 -0.011014 0.000356 0.316357 10.082827\n14232 56.891024 -0.004459 -0.002451 -0.010860 -0.003452 0.302793 10.082505\n14233 56.896859 -0.004213 -0.002434 -0.010725 0.003119 0.301632 10.088251\n14234 56.903107 -0.004400 -0.002775 -0.010078 0.020514 0.303589 10.090502\n14235 56.909023 -0.004536 -0.002752 -0.010003 0.026748 0.294670 10.101155\n14236 56.915116 -0.004512 -0.003155 -0.009950 0.010516 0.296745 10.113416\n14237 56.920977 -0.004450 -0.003237 -0.009862 0.004532 0.316260 10.111403\n14238 56.927303 -0.004255 -0.002845 -0.010317 0.000124 0.328944 10.113352\n14239 56.933214 -0.004235 -0.002398 -0.010645 0.001873 0.313110 10.103715\n14240 56.939119 -0.004436 -0.002032 -0.010571 0.013475 0.300354 10.082544\n14241 56.945244 -0.004463 -0.002356 -0.009812 0.017283 0.310152 10.081894\n14242 56.951226 -0.003507 -0.002203 -0.008857 0.009970 0.305597 10.082572\n14243 56.957247 -0.003218 -0.002164 -0.008987 0.005418 0.310767 10.080340\n14244 56.963372 -0.003441 -0.002693 -0.009753 -0.000275 0.336030 10.077582\n14245 56.969344 -0.003467 -0.002829 -0.010053 0.002714 0.337243 10.082867\n14246 56.975473 -0.003639 -0.002884 -0.010415 0.010078 0.319543 10.116888\n14247 56.981348 -0.003685 -0.002605 -0.010295 0.011910 0.313025 10.129164\n14248 56.987487 -0.003442 -0.002276 -0.010003 0.014221 0.325872 10.108562\n14249 56.993427 -0.003462 -0.002570 -0.009824 0.011490 0.322920 10.096195\n14250 56.999550 -0.004058 -0.002637 -0.009384 0.000650 0.305240 10.079654\n14251 57.005543 -0.004218 -0.002555 -0.009246 -0.001077 0.314002 10.077483\n14252 57.011578 -0.004719 -0.002611 -0.009592 -0.000182 0.339407 10.094353\n14253 57.017739 -0.004798 -0.002503 -0.009731 0.003688 0.336602 10.102598\n14254 57.023698 -0.004985 -0.002351 -0.010226 0.016708 0.307559 10.092880\n14255 57.029630 -0.004751 -0.002324 -0.010474 0.021401 0.301452 10.091566\n14256 57.035756 -0.003488 -0.002241 -0.010426 0.019414 0.313806 10.100884\n14257 57.041745 -0.003253 -0.002474 -0.010500 0.018414 0.307243 10.097548\n14258 57.047834 -0.003725 -0.003048 -0.010166 0.006553 0.310468 10.093577\n14259 57.053816 -0.004034 -0.003546 -0.009858 -0.006475 0.331160 10.091916\n14260 57.059954 -0.004273 -0.003388 -0.009979 -0.006701 0.348387 10.106267\n14261 57.065944 -0.004570 -0.002937 -0.009978 0.001905 0.333133 10.108638\n14262 57.071944 -0.004944 -0.001875 -0.009661 0.016316 0.322790 10.095200\n14263 57.078068 -0.004948 -0.001496 -0.009563 0.022447 0.330343 10.088223\n14264 57.084193 -0.004397 -0.002215 -0.010021 0.019745 0.325227 10.092868\n14265 57.090269 -0.004302 -0.002151 -0.009887 0.021397 0.316540 10.097809\n14266 57.096217 -0.003630 -0.002442 -0.009468 0.012092 0.322783 10.096922\n14267 57.102209 -0.003324 -0.002912 -0.009463 0.010844 0.332199 10.104933\n14268 57.108213 -0.003718 -0.002718 -0.010207 0.022280 0.316005 10.122364\n14269 57.114165 -0.004296 -0.002431 -0.010463 0.022812 0.301565 10.120434\n14270 57.120364 -0.004957 -0.002552 -0.010114 0.005201 0.296200 10.095341\n14271 57.126370 -0.004753 -0.002535 -0.009812 0.003044 0.310490 10.093610\n14272 57.132392 -0.004159 -0.002387 -0.009612 0.019242 0.315302 10.094976\n14273 57.138520 -0.003893 -0.002649 -0.009572 0.026040 0.306708 10.098053\n14274 57.144506 -0.003579 -0.002548 -0.009440 0.032337 0.331287 10.096588\n14275 57.150648 -0.003678 -0.002369 -0.009333 0.025748 0.338837 10.101941\n14276 57.156562 -0.003954 -0.001758 -0.009819 -0.002303 0.311032 10.111250\n14277 57.162718 -0.004310 -0.001511 -0.009820 -0.012467 0.303201 10.108715\n14278 57.168592 -0.004912 -0.001410 -0.009593 -0.010193 0.307622 10.096716\n14279 57.174701 -0.004782 -0.001470 -0.009532 -0.004594 0.304492 10.093797\n14280 57.180838 -0.003713 -0.002035 -0.009429 0.011654 0.299708 10.108008\n14281 57.186738 -0.003488 -0.002609 -0.009557 0.011707 0.306102 10.110633\n14282 57.192821 -0.003994 -0.003412 -0.010252 0.004350 0.328899 10.104579\n14283 57.198788 -0.004390 -0.003535 -0.010215 -0.000999 0.329064 10.103952\n14284 57.204941 -0.004358 -0.003018 -0.010802 0.003268 0.306281 10.080617\n14285 57.211077 -0.004491 -0.002629 -0.010771 0.018155 0.309020 10.078025\n14286 57.217076 -0.004548 -0.002481 -0.010098 0.037753 0.342937 10.110102\n14287 57.223070 -0.004512 -0.002445 -0.009609 0.039518 0.336576 10.131105\n14288 57.229227 -0.004825 -0.002970 -0.009277 0.038078 0.316689 10.141451\n14289 57.235632 -0.004540 -0.003184 -0.009878 0.015524 0.326775 10.121956\n14290 57.241235 -0.004138 -0.003026 -0.010232 0.002916 0.327121 10.113173\n14291 57.247747 -0.003982 -0.002158 -0.009887 0.002439 0.304153 10.089054\n14292 57.253275 -0.004085 -0.002072 -0.009783 0.003666 0.295111 10.084239\n14293 57.259754 -0.003643 -0.002436 -0.009869 0.006534 0.311963 10.087601\n14294 57.265376 -0.003297 -0.002643 -0.010163 0.007479 0.317522 10.090672\n14295 57.271591 -0.003150 -0.002244 -0.010564 0.008846 0.294681 10.094125\n14296 57.277504 -0.003688 -0.002169 -0.010623 0.010608 0.294983 10.112200\n14297 57.283962 -0.004122 -0.002078 -0.010102 0.005652 0.320280 10.128093\n14298 57.289597 -0.004194 -0.002322 -0.009956 0.006843 0.325332 10.125575\n14299 57.295695 -0.004607 -0.002723 -0.010375 0.032050 0.303966 10.104009\n14300 57.301535 -0.004844 -0.002673 -0.010233 0.035413 0.304140 10.093033\n14301 57.307726 -0.004888 -0.002441 -0.009873 0.030766 0.315739 10.088165\n14302 57.313618 -0.004761 -0.002612 -0.010049 0.029023 0.308270 10.082261\n14303 57.319846 -0.004638 -0.003205 -0.010074 0.017920 0.298915 10.074725\n14304 57.325851 -0.004407 -0.003321 -0.010280 0.005300 0.316869 10.091781\n14305 57.331717 -0.003619 -0.002491 -0.010661 0.000850 0.331690 10.105007\n14306 57.337769 -0.003601 -0.002251 -0.010684 0.000172 0.324266 10.094446\n14307 57.343842 -0.004946 -0.002122 -0.010705 -0.005566 0.312086 10.084903\n14308 57.349980 -0.005202 -0.002123 -0.010616 -0.007691 0.315618 10.078243\n14309 57.355894 -0.004666 -0.002431 -0.010345 0.005011 0.310522 10.093287\n14310 57.361921 -0.004413 -0.002738 -0.010400 0.012915 0.308865 10.105237\n14311 57.368068 -0.004203 -0.002833 -0.010136 0.023985 0.322565 10.110094\n14312 57.374066 -0.004088 -0.002885 -0.010199 0.028591 0.324013 10.107178\n14313 57.380074 -0.003953 -0.002808 -0.010354 0.020672 0.320064 10.101916\n14314 57.386248 -0.003871 -0.002688 -0.010332 0.013957 0.318647 10.093787\n14315 57.392182 -0.004268 -0.002759 -0.010725 0.009374 0.335103 10.098598\n14316 57.398305 -0.004291 -0.002790 -0.010749 0.006308 0.338051 10.114090\n14317 57.404300 -0.004258 -0.002440 -0.010424 0.009800 0.309495 10.115572\n14318 57.410416 -0.004541 -0.002546 -0.010336 0.014387 0.301529 10.109575\n14319 57.416533 -0.004888 -0.002564 -0.010556 0.020083 0.326795 10.108967\n14320 57.422413 -0.004668 -0.002583 -0.010368 0.021018 0.337778 10.113400\n14321 57.428493 -0.004781 -0.002762 -0.010170 0.012166 0.324004 10.091320\n14322 57.434501 -0.004701 -0.002697 -0.009926 0.006534 0.325782 10.084888\n14323 57.440615 -0.004362 -0.002563 -0.009842 0.005691 0.336506 10.102719\n14324 57.446540 -0.004427 -0.002381 -0.009919 0.003998 0.325302 10.105380\n14325 57.452528 -0.004537 -0.002177 -0.010146 0.006478 0.308384 10.100114\n14326 57.458602 -0.004601 -0.002224 -0.010281 0.011193 0.312727 10.102449\n14327 57.464700 -0.004305 -0.002126 -0.010630 0.009687 0.320405 10.074590\n14328 57.470704 -0.004222 -0.001825 -0.010671 0.012069 0.311245 10.065404\n14329 57.476804 -0.004735 -0.002032 -0.010795 0.011285 0.304150 10.076735\n14330 57.482763 -0.004880 -0.002315 -0.010628 0.016361 0.319556 10.081017\n14331 57.488771 -0.004653 -0.002106 -0.009972 0.029985 0.328937 10.093919\n14332 57.494871 -0.003989 -0.001914 -0.009851 0.034449 0.316130 10.104856\n14333 57.501029 -0.003407 -0.002271 -0.009735 0.027992 0.318555 10.121626\n14334 57.507093 -0.003527 -0.002336 -0.009907 0.017063 0.340722 10.128783\n14335 57.513057 -0.003270 -0.002007 -0.009815 0.017024 0.337291 10.133964\n14336 57.519141 -0.003603 -0.001833 -0.009883 0.017564 0.319408 10.126971\n14337 57.525198 -0.003961 -0.002444 -0.010049 0.017033 0.315946 10.108404\n14338 57.531247 -0.004206 -0.002510 -0.009853 0.007377 0.321977 10.109190\n14339 57.537160 -0.004233 -0.002519 -0.009752 -0.004468 0.320091 10.109660\n14340 57.543256 -0.004422 -0.002659 -0.009787 -0.002003 0.314917 10.109260\n14341 57.549391 -0.004221 -0.002584 -0.010115 0.002979 0.327674 10.114610\n14342 57.555402 -0.004230 -0.002770 -0.010272 0.004004 0.341677 10.110677\n14343 57.561333 -0.004397 -0.002910 -0.010373 0.013104 0.333441 10.096741\n14344 57.567335 -0.004566 -0.002835 -0.010443 0.012296 0.317651 10.085363\n14345 57.573519 -0.004809 -0.002483 -0.009845 0.018809 0.326069 10.087275\n14346 57.579513 -0.004567 -0.002380 -0.009588 0.020980 0.330414 10.105186\n14347 57.585507 -0.004274 -0.002490 -0.010337 0.033547 0.311091 10.127320\n14348 57.591599 -0.004501 -0.002424 -0.010518 0.037339 0.307814 10.130420\n14349 57.597688 -0.004339 -0.002025 -0.010161 0.036209 0.325197 10.114669\n14350 57.603707 -0.004153 -0.002272 -0.009807 0.032427 0.330393 10.114266\n14351 57.609840 -0.003959 -0.002783 -0.009187 0.020331 0.315631 10.093044\n14352 57.616425 -0.003792 -0.002757 -0.009718 0.010772 0.325714 10.076826\n14353 57.621891 -0.003789 -0.002756 -0.010163 0.009852 0.335308 10.093500\n14354 57.628276 -0.004193 -0.002475 -0.010174 0.004763 0.324589 10.099017\n14355 57.633919 -0.004303 -0.002384 -0.009892 0.003947 0.310519 10.097454\n14356 57.640340 -0.005257 -0.002537 -0.009706 0.000392 0.304873 10.118452\n14357 57.645957 -0.005425 -0.002675 -0.009971 0.002117 0.315563 10.121512\n14358 57.652462 -0.004868 -0.002713 -0.009951 0.014981 0.315118 10.114457\n14359 57.658131 -0.004815 -0.002595 -0.010100 0.018812 0.315241 10.116076\n14360 57.664326 -0.004860 -0.002588 -0.010493 0.019407 0.345295 10.117071\n14361 57.670252 -0.004578 -0.002545 -0.010394 0.016824 0.347438 10.121397\n14362 57.676463 -0.004031 -0.002281 -0.010013 0.020512 0.309918 10.116910\n14363 57.682378 -0.004394 -0.002413 -0.009841 0.025038 0.309324 10.109004\n14364 57.688488 -0.004369 -0.003175 -0.009678 0.022504 0.344312 10.110354\n14365 57.694377 -0.004132 -0.003533 -0.009717 0.024002 0.346184 10.125278\n14366 57.700618 -0.004083 -0.003647 -0.010206 0.025495 0.311494 10.132894\n14367 57.706441 -0.004404 -0.003265 -0.010417 0.021551 0.315247 10.127293\n14368 57.712548 -0.004542 -0.002648 -0.010610 0.020007 0.312558 10.103236\n14369 57.718419 -0.004653 -0.002465 -0.010623 0.013634 0.295027 10.093578\n14370 57.724591 -0.004303 -0.002309 -0.010706 0.007005 0.269337 10.097009\n14371 57.730585 -0.004441 -0.002465 -0.010995 0.002607 0.292305 10.107046\n14372 57.736716 -0.004517 -0.002441 -0.010537 -0.003477 0.341895 10.117421\n14373 57.742738 -0.004342 -0.002450 -0.010146 0.002358 0.334477 10.115974\n14374 57.748815 -0.004249 -0.002639 -0.010044 0.010238 0.313641 10.092703\n14375 57.754693 -0.004175 -0.002930 -0.009933 0.005214 0.322895 10.076946\n14376 57.760872 -0.003774 -0.002601 -0.010240 0.008256 0.321475 10.095559\n14377 57.766757 -0.003937 -0.002727 -0.010287 0.013171 0.301732 10.109357\n14378 57.773016 -0.004721 -0.003055 -0.010330 0.014509 0.296711 10.113851\n14379 57.778880 -0.004919 -0.002765 -0.010285 0.008932 0.318911 10.113897\n14380 57.784944 -0.004511 -0.002628 -0.010504 0.009444 0.335523 10.114190\n14381 57.790984 -0.004641 -0.002423 -0.010637 0.011201 0.326032 10.110609\n14382 57.797109 -0.004957 -0.002234 -0.010661 0.012937 0.327009 10.092357\n14383 57.803069 -0.004693 -0.002425 -0.010541 0.005911 0.333471 10.093247\n14384 57.809134 -0.004383 -0.002717 -0.009881 -0.007529 0.309043 10.094881\n14385 57.815143 -0.004334 -0.002532 -0.009879 -0.003842 0.291621 10.087442\n14386 57.821152 -0.004066 -0.002142 -0.010007 0.009290 0.315065 10.081399\n14387 57.827277 -0.003752 -0.002024 -0.009744 0.008382 0.331964 10.095039\n14388 57.833227 -0.003690 -0.002624 -0.009629 0.004677 0.323119 10.118069\n14389 57.839318 -0.003917 -0.002800 -0.009747 0.006631 0.312494 10.120594\n14390 57.845313 -0.004305 -0.002963 -0.010068 0.001513 0.335305 10.114394\n14391 57.851473 -0.004254 -0.002915 -0.010186 0.001065 0.345793 10.101633\n14392 57.857450 -0.004323 -0.002501 -0.010710 0.013911 0.303508 10.062022\n14393 57.863507 -0.004792 -0.002415 -0.010719 0.020414 0.293580 10.058624\n14394 57.869447 -0.004604 -0.002472 -0.010298 0.025865 0.322529 10.094543\n14395 57.875422 -0.004171 -0.002549 -0.010097 0.023354 0.325254 10.112556\n14396 57.881640 -0.004273 -0.003165 -0.010024 0.014558 0.303621 10.106771\n14397 57.887462 -0.004452 -0.003423 -0.009817 0.004953 0.308571 10.084043\n14398 57.893608 -0.004632 -0.003137 -0.010295 -0.000557 0.339748 10.093954\n14399 57.899888 -0.004510 -0.002702 -0.010495 0.001666 0.335909 10.104399\n14400 57.905727 -0.004555 -0.002257 -0.010102 0.015778 0.307075 10.092437\n14401 57.911736 -0.004658 -0.002406 -0.010243 0.018388 0.303710 10.089648\n14402 57.917885 -0.004696 -0.003181 -0.009940 -0.004181 0.320227 10.114979\n14403 57.923854 -0.004414 -0.003229 -0.009887 -0.008427 0.309565 10.115102\n14404 57.929809 -0.004329 -0.002932 -0.010116 0.002659 0.305747 10.096804\n14405 57.935795 -0.004575 -0.002766 -0.010014 0.001906 0.329292 10.093743\n14406 57.941920 -0.005355 -0.002288 -0.010254 -0.005633 0.343715 10.111519\n14407 57.948147 -0.005426 -0.002152 -0.010669 -0.001196 0.318215 10.115246\n14408 57.954034 -0.005240 -0.002749 -0.010722 0.019125 0.299352 10.114324\n14409 57.959963 -0.004667 -0.003111 -0.010511 0.019964 0.316504 10.116464\n14410 57.966210 -0.003440 -0.003265 -0.010143 0.015877 0.324983 10.108365\n14411 57.972120 -0.003745 -0.003102 -0.010118 0.011768 0.304628 10.110445\n14412 57.978152 -0.004326 -0.002725 -0.009757 0.004072 0.309781 10.114645\n14413 57.984119 -0.004505 -0.002507 -0.009896 0.002808 0.336353 10.119691\n14414 57.990217 -0.004738 -0.002487 -0.010353 0.004550 0.334349 10.126527\n14415 57.996327 -0.004541 -0.002625 -0.010432 0.012956 0.313751 10.126298\n14416 58.002928 -0.004380 -0.002833 -0.010478 0.018018 0.309313 10.106934\n14417 58.009067 -0.004191 -0.002890 -0.010542 0.006323 0.331426 10.094687\n14418 58.014664 -0.003283 -0.002987 -0.010193 -0.002887 0.329625 10.085572\n14419 58.021129 -0.003567 -0.003104 -0.010280 -0.002256 0.325120 10.081484\n14420 58.026652 -0.003868 -0.003144 -0.010108 0.005945 0.349967 10.083540\n14421 58.033267 -0.004049 -0.002674 -0.009734 0.012922 0.339478 10.102519\n14422 58.038747 -0.004241 -0.002511 -0.009543 0.010255 0.311891 10.101919\n14423 58.045246 -0.004541 -0.002999 -0.009909 0.016305 0.312212 10.102304\n14424 58.050674 -0.004386 -0.003168 -0.009817 0.018758 0.334405 10.103153\n14425 58.057326 -0.004317 -0.002854 -0.009320 0.023013 0.335519 10.111129\n14426 58.062757 -0.004289 -0.002785 -0.009625 0.024086 0.325224 10.111851\n14427 58.069172 -0.004733 -0.002834 -0.010373 0.021752 0.338260 10.106306\n14428 58.074733 -0.004615 -0.003069 -0.010225 0.013020 0.348051 10.105872\n14429 58.081378 -0.004313 -0.003142 -0.009578 0.008608 0.348414 10.105093\n14430 58.086914 -0.004124 -0.002520 -0.009698 0.011492 0.332444 10.096653\n14431 58.093240 -0.004469 -0.002066 -0.010074 0.015499 0.335477 10.072890\n14432 58.099134 -0.004401 -0.002132 -0.010346 0.025929 0.341026 10.075957\n14433 58.105545 -0.003917 -0.002412 -0.010616 0.022958 0.299817 10.085973\n14434 58.111242 -0.003955 -0.002827 -0.010645 0.013842 0.289659 10.086010\n14435 58.117436 -0.004672 -0.002941 -0.010275 -0.003786 0.332910 10.091458\n14436 58.123306 -0.004599 -0.002525 -0.009913 0.000924 0.347805 10.093922\n14437 58.129271 -0.004569 -0.001401 -0.009727 0.021776 0.317916 10.098005\n14438 58.135213 -0.004769 -0.001498 -0.009677 0.022993 0.307037 10.097339\n14439 58.141331 -0.004834 -0.002276 -0.009523 0.012263 0.323705 10.088465\n14440 58.147420 -0.004817 -0.002171 -0.009414 0.021933 0.320888 10.087100\n14441 58.153423 -0.004682 -0.001632 -0.009304 0.035669 0.294239 10.073158\n14442 58.159436 -0.004631 -0.001872 -0.009668 0.030411 0.299130 10.074913\n14443 58.165557 -0.004543 -0.002532 -0.010159 0.017465 0.319481 10.092860\n14444 58.171474 -0.004591 -0.002518 -0.010391 0.016262 0.315224 10.097856\n14445 58.177676 -0.004891 -0.001789 -0.010238 0.029579 0.300421 10.076049\n14446 58.183590 -0.005000 -0.001570 -0.010471 0.031272 0.316487 10.077397\n14447 58.189845 -0.004463 -0.002539 -0.010743 0.032149 0.347810 10.122611\n14448 58.195706 -0.004070 -0.003232 -0.010582 0.027661 0.336192 10.126170\n14449 58.201812 -0.004479 -0.003169 -0.010473 0.024793 0.315364 10.085482\n14450 58.208224 -0.004799 -0.003049 -0.010179 0.013090 0.335244 10.074123\n14451 58.213862 -0.004018 -0.002108 -0.009429 -0.001933 0.341914 10.068508\n14452 58.219948 -0.003850 -0.001555 -0.009671 -0.001583 0.317658 10.067477\n14453 58.225958 -0.004236 -0.001713 -0.009951 0.004067 0.298881 10.077251\n14454 58.232000 -0.004193 -0.002121 -0.009933 0.008396 0.320603 10.084529\n14455 58.237976 -0.003959 -0.002478 -0.010498 0.024654 0.342288 10.122896\n14456 58.244103 -0.004181 -0.002237 -0.010541 0.024303 0.329123 10.120332\n14457 58.250138 -0.004232 -0.001943 -0.010067 0.017011 0.321193 10.099004\n14458 58.256158 -0.004120 -0.001870 -0.009779 0.010326 0.332930 10.087915\n14459 58.262143 -0.004165 -0.001806 -0.009807 -0.005681 0.326978 10.072014\n14460 58.268277 -0.004273 -0.002018 -0.010020 -0.000308 0.308465 10.076036\n14461 58.274280 -0.004861 -0.002437 -0.010040 0.024547 0.307442 10.087817\n14462 58.280332 -0.004924 -0.002531 -0.009912 0.026490 0.323715 10.077362\n14463 58.286583 -0.004319 -0.001988 -0.009911 0.009845 0.313573 10.064733\n14464 58.292367 -0.004338 -0.001715 -0.009829 0.007890 0.305237 10.061600\n14465 58.298469 -0.004503 -0.001990 -0.009595 0.002751 0.334511 10.076133\n14466 58.304460 -0.004407 -0.002182 -0.009539 -0.000154 0.345751 10.089165\n14467 58.310794 -0.004324 -0.002495 -0.009625 0.011650 0.327906 10.090158\n14468 58.316533 -0.004395 -0.002761 -0.010030 0.015004 0.320126 10.085155\n14469 58.322727 -0.004546 -0.002798 -0.010102 0.008709 0.331958 10.086600\n14470 58.328519 -0.004258 -0.002686 -0.009982 0.008351 0.328928 10.088780\n14471 58.334728 -0.003781 -0.002686 -0.009646 0.015390 0.310276 10.095748\n14472 58.340669 -0.003726 -0.002855 -0.009563 0.025217 0.316165 10.098778\n14473 58.346943 -0.004117 -0.003159 -0.009480 0.017656 0.329650 10.108464\n14474 58.353017 -0.004070 -0.002821 -0.009275 0.011871 0.321199 10.098351\n14475 58.358849 -0.003982 -0.002193 -0.009357 0.006486 0.300262 10.087256\n14476 58.364808 -0.004083 -0.002018 -0.009443 0.010091 0.299663 10.098826\n14477 58.370827 -0.004047 -0.001628 -0.009870 0.022498 0.313282 10.114076\n14478 58.376930 -0.003959 -0.001791 -0.010229 0.028801 0.307355 10.105211\n14479 58.383110 -0.004173 -0.001801 -0.010689 0.024768 0.303585 10.089843\n14480 58.389031 -0.004575 -0.002058 -0.010643 0.023116 0.314921 10.096672\n14481 58.394964 -0.004902 -0.002353 -0.010525 0.010235 0.329702 10.111098\n14482 58.401164 -0.004475 -0.002348 -0.010468 0.008757 0.326415 10.114096\n14483 58.407263 -0.004192 -0.002433 -0.011029 0.014182 0.316093 10.096165\n14484 58.414098 -0.004481 -0.002642 -0.010608 0.023670 0.335890 10.083412\n14485 58.420220 -0.004233 -0.002520 -0.010336 0.030073 0.333963 10.089281\n14486 58.426313 -0.003715 -0.002036 -0.009972 0.023136 0.305722 10.095012\n14487 58.432439 -0.003525 -0.002225 -0.009981 0.025310 0.307435 10.096045\n14488 58.438345 -0.004245 -0.002504 -0.010122 0.024741 0.328446 10.100375\n14489 58.444472 -0.004366 -0.002550 -0.009821 0.026970 0.325890 10.096668\n14490 58.450574 -0.004664 -0.002320 -0.009589 0.025230 0.303514 10.112711\n14491 58.456460 -0.004870 -0.002405 -0.009921 0.019039 0.304122 10.122347\n14492 58.462673 -0.004811 -0.001997 -0.009997 0.009633 0.307649 10.125309\n14493 58.468626 -0.004716 -0.001945 -0.010139 0.007208 0.297688 10.124411\n14494 58.474708 -0.004599 -0.002453 -0.010121 0.014915 0.303619 10.100594\n14495 58.480600 -0.004471 -0.003045 -0.010036 0.011277 0.321130 10.085299\n14496 58.486668 -0.003827 -0.003052 -0.010391 0.006472 0.346753 10.092426\n14497 58.492845 -0.003590 -0.002647 -0.010538 0.007521 0.326773 10.104582\n14498 58.498723 -0.004128 -0.002523 -0.010794 0.015305 0.305401 10.102080\n14499 58.504769 -0.004352 -0.002826 -0.010547 0.016051 0.314210 10.095836\n14500 58.510837 -0.004283 -0.002908 -0.009892 0.022437 0.312823 10.081629\n14501 58.516990 -0.004133 -0.002755 -0.009617 0.024999 0.309063 10.084143\n14502 58.522983 -0.003980 -0.002424 -0.009593 0.016736 0.326733 10.086111\n14503 58.529097 -0.004103 -0.002308 -0.009717 0.010854 0.343078 10.098128\n14504 58.535089 -0.004443 -0.001839 -0.010522 0.008815 0.336204 10.105680\n14505 58.541019 -0.004746 -0.001877 -0.011027 0.012934 0.312265 10.095599\n14506 58.547002 -0.004611 -0.002791 -0.010938 0.010389 0.316637 10.092010\n14507 58.553149 -0.004457 -0.002867 -0.010767 0.004471 0.334148 10.097644\n14508 58.559172 -0.004093 -0.002466 -0.009999 0.016956 0.337702 10.095285\n14509 58.565170 -0.003998 -0.002085 -0.009943 0.023329 0.331040 10.089673\n14510 58.571281 -0.004480 -0.002232 -0.010320 0.009978 0.330962 10.075169\n14511 58.577298 -0.004524 -0.002579 -0.010214 0.005092 0.334354 10.069485\n14512 58.583461 -0.004123 -0.002770 -0.010052 0.005841 0.334547 10.079714\n14513 58.589312 -0.004330 -0.002596 -0.010061 0.004422 0.339895 10.082561\n14514 58.595366 -0.004382 -0.002096 -0.010420 -0.002763 0.355199 10.082984\n14515 58.601490 -0.004441 -0.002124 -0.010539 0.002041 0.346584 10.087504\n14516 58.607427 -0.004266 -0.002803 -0.010156 0.020380 0.312067 10.087343\n14517 58.613626 -0.004349 -0.003082 -0.009796 0.021276 0.315646 10.080221\n14518 58.619566 -0.004236 -0.003557 -0.009505 0.001951 0.339711 10.078241\n14519 58.625680 -0.004106 -0.003588 -0.009502 -0.006356 0.334046 10.087198\n14520 58.631751 -0.004043 -0.003224 -0.009707 0.008653 0.312770 10.090556\n14521 58.637654 -0.004110 -0.002982 -0.009932 0.013295 0.315797 10.091625\n14522 58.643839 -0.004533 -0.002578 -0.010256 0.026934 0.332230 10.106984\n14523 58.649843 -0.004506 -0.002802 -0.010039 0.031269 0.322201 10.114038\n14524 58.655947 -0.004543 -0.003145 -0.009267 0.027799 0.310970 10.110911\n14525 58.661884 -0.004414 -0.003125 -0.009281 0.023054 0.330077 10.096384\n14526 58.668241 -0.004170 -0.002992 -0.009895 0.008732 0.357980 10.061941\n14527 58.674444 -0.004269 -0.002481 -0.010336 -0.009434 0.326888 10.064781\n14528 58.679947 -0.004369 -0.002672 -0.010269 -0.006560 0.317383 10.074974\n14529 58.686627 -0.004267 -0.003137 -0.009778 0.001864 0.326102 10.090077\n14530 58.692245 -0.004215 -0.003143 -0.009614 0.006628 0.322017 10.109734\n14531 58.698612 -0.004465 -0.002871 -0.009501 0.006663 0.308866 10.124118\n14532 58.704302 -0.004744 -0.002777 -0.009537 0.002415 0.308117 10.118307\n14533 58.710570 -0.004607 -0.002640 -0.009867 -0.009447 0.323951 10.100645\n14534 58.716228 -0.004418 -0.002291 -0.009909 -0.003495 0.320576 10.102050\n14535 58.722716 -0.004606 -0.001502 -0.010534 0.008804 0.319428 10.106066\n14536 58.728319 -0.004743 -0.001496 -0.010701 0.011815 0.327549 10.114136\n14537 58.734882 -0.004241 -0.002501 -0.010288 0.017809 0.325807 10.115837\n14538 58.740371 -0.004138 -0.003021 -0.010019 0.023544 0.316512 10.111377\n14539 58.746693 -0.004333 -0.003501 -0.009921 0.026202 0.315754 10.113182\n14540 58.752380 -0.004427 -0.003101 -0.009663 0.018008 0.329488 10.107553\n14541 58.758645 -0.004361 -0.002683 -0.009921 0.005989 0.335222 10.090113\n14542 58.764596 -0.004210 -0.002771 -0.010248 0.005919 0.323494 10.078725\n14543 58.770668 -0.004686 -0.002143 -0.011032 0.010981 0.312487 10.061141\n14544 58.776534 -0.004858 -0.002126 -0.011310 0.007144 0.323616 10.061330\n14545 58.782767 -0.004310 -0.002192 -0.011332 -0.001451 0.341508 10.066039\n14546 58.788767 -0.003787 -0.002569 -0.010786 0.002689 0.337582 10.074274\n14547 58.794874 -0.003575 -0.002864 -0.009769 0.016659 0.337748 10.091591\n14548 58.800846 -0.003356 -0.002751 -0.009647 0.009325 0.345547 10.106159\n14549 58.806893 -0.003034 -0.002116 -0.010215 -0.015491 0.343371 10.111287\n14550 58.812866 -0.003335 -0.001910 -0.010493 -0.011144 0.331220 10.103969\n14551 58.818860 -0.004164 -0.001998 -0.011065 0.017592 0.322838 10.114184\n14552 58.825245 -0.004099 -0.002062 -0.010998 0.026888 0.322741 10.120387\n14553 58.830930 -0.004311 -0.002437 -0.010607 0.024601 0.306463 10.111259\n14554 58.837053 -0.004613 -0.002640 -0.010287 0.019356 0.309522 10.105213\n14555 58.843014 -0.004691 -0.002687 -0.009237 0.006027 0.327773 10.091430\n14556 58.849156 -0.004642 -0.002387 -0.009400 0.005346 0.321536 10.072123\n14557 58.855335 -0.004544 -0.001995 -0.009918 0.016832 0.297395 10.082995\n14558 58.861310 -0.004684 -0.001921 -0.010209 0.018472 0.307382 10.096326\n14559 58.867515 -0.005002 -0.001512 -0.010986 0.018669 0.329091 10.106046\n14560 58.873301 -0.004926 -0.001426 -0.011325 0.019840 0.320973 10.104401\n14561 58.879308 -0.004941 -0.002029 -0.010959 0.024817 0.301442 10.100723\n14562 58.885338 -0.004847 -0.002548 -0.010429 0.019028 0.309328 10.103925\n14563 58.891514 -0.004851 -0.003273 -0.009685 0.006527 0.348263 10.111779\n14564 58.897438 -0.004642 -0.003420 -0.009531 0.005025 0.350676 10.101217\n14565 58.903423 -0.004655 -0.003272 -0.009850 -0.006891 0.325147 10.087381\n14566 58.909626 -0.004742 -0.002926 -0.010348 -0.004766 0.324736 10.092711\n14567 58.915628 -0.004949 -0.002561 -0.010752 0.014327 0.331429 10.106733\n14568 58.921766 -0.004748 -0.002527 -0.010500 0.019863 0.315025 10.104211\n14569 58.927668 -0.004663 -0.002842 -0.009815 0.013169 0.305552 10.095942\n14570 58.933869 -0.004540 -0.002974 -0.009358 0.008007 0.325456 10.096125\n14571 58.939816 -0.003994 -0.003084 -0.009418 0.006139 0.332956 10.100780\n14572 58.945868 -0.003777 -0.003023 -0.009895 0.004825 0.321745 10.098299\n14573 58.951891 -0.004360 -0.001962 -0.010586 0.008162 0.324288 10.098804\n14574 58.958051 -0.004761 -0.001961 -0.010730 0.016258 0.334093 10.107843\n14575 58.963810 -0.004488 -0.002179 -0.010676 0.016921 0.308738 10.117293\n14576 58.969943 -0.004394 -0.002857 -0.010052 0.014246 0.303080 10.098900\n14577 58.975929 -0.004355 -0.003418 -0.010025 0.012431 0.319577 10.070861\n14578 58.982099 -0.003953 -0.003104 -0.010274 0.012172 0.324391 10.088686\n14579 58.987930 -0.003877 -0.002175 -0.010306 -0.001720 0.314484 10.110984\n14580 58.994155 -0.004175 -0.001953 -0.010334 -0.002153 0.318194 10.102738\n14581 59.000163 -0.005069 -0.001777 -0.010503 0.006089 0.336097 10.099324\n14582 59.006167 -0.005405 -0.002020 -0.010628 0.012610 0.340689 10.104320\n14583 59.012153 -0.005652 -0.002406 -0.010483 0.019287 0.320224 10.114700\n14584 59.018231 -0.005588 -0.002572 -0.010099 0.018804 0.310343 10.105678\n14585 59.024346 -0.005236 -0.002954 -0.009580 0.023818 0.322899 10.105872\n14586 59.030237 -0.004818 -0.002909 -0.009594 0.028986 0.321185 10.111509\n14587 59.036369 -0.004112 -0.002266 -0.010253 0.023198 0.298666 10.100323\n14588 59.042364 -0.003973 -0.002319 -0.010536 0.016137 0.308549 10.096105\n14589 59.048283 -0.003785 -0.002168 -0.010449 0.010751 0.335842 10.110864\n14590 59.054553 -0.004134 -0.002004 -0.010469 0.014991 0.328717 10.123316\n14591 59.060418 -0.004534 -0.002259 -0.010520 0.018576 0.312230 10.112052\n14592 59.066855 -0.004611 -0.002783 -0.010247 0.012130 0.318843 10.100298\n14593 59.072570 -0.004318 -0.003656 -0.009595 -0.007269 0.316150 10.098126\n14594 59.078747 -0.004425 -0.003488 -0.009581 -0.014428 0.311669 10.100409\n14595 59.084656 -0.005209 -0.001863 -0.010453 -0.009549 0.318243 10.107673\n14596 59.090759 -0.005259 -0.001480 -0.010619 -0.003402 0.336866 10.104567\n14597 59.096748 -0.005111 -0.002117 -0.010651 0.003957 0.355289 10.100904\n14598 59.102830 -0.004989 -0.002728 -0.010671 0.008721 0.341416 10.099097\n14599 59.108861 -0.004884 -0.002955 -0.011117 0.011141 0.315632 10.086178\n14600 59.114802 -0.004793 -0.003072 -0.010909 0.008722 0.317622 10.085016\n14601 59.120942 -0.003776 -0.002811 -0.010162 0.007498 0.317755 10.104907\n14602 59.127598 -0.003683 -0.002287 -0.010192 0.010412 0.316362 10.115570\n14603 59.133248 -0.004680 -0.001126 -0.010385 -0.000534 0.327471 10.110093\n14604 59.139596 -0.004966 -0.000929 -0.010249 0.004160 0.334533 10.087921\n14605 59.145127 -0.004954 -0.001392 -0.010086 0.018706 0.325972 10.081192\n14606 59.151516 -0.004782 -0.001842 -0.009843 0.025332 0.321630 10.098698\n14607 59.157152 -0.005015 -0.002083 -0.009662 0.022045 0.324331 10.107315\n14608 59.163686 -0.004675 -0.002387 -0.009796 0.015412 0.330903 10.116515\n14609 59.169240 -0.004092 -0.002754 -0.010110 0.014626 0.333894 10.115807\n14610 59.175738 -0.003743 -0.002292 -0.010494 0.020269 0.332984 10.100297\n14611 59.181371 -0.003997 -0.001814 -0.010495 0.018935 0.336357 10.095146\n14612 59.187817 -0.004734 -0.001322 -0.009998 0.010505 0.327025 10.100473\n14613 59.193325 -0.004949 -0.001413 -0.009376 0.011414 0.319188 10.094493\n14614 59.199701 -0.005162 -0.002153 -0.008839 0.009270 0.330770 10.076732\n14615 59.205460 -0.004827 -0.002424 -0.008878 -0.000951 0.339256 10.081118\n14616 59.211706 -0.003343 -0.002330 -0.009805 0.004032 0.318595 10.094212\n14617 59.217587 -0.003244 -0.002217 -0.010179 0.006049 0.307371 10.099755\n14618 59.223561 -0.003695 -0.001986 -0.010226 0.009487 0.318220 10.108050\n14619 59.229588 -0.003630 -0.001588 -0.010251 0.015803 0.323507 10.116289\n14620 59.235727 -0.003562 -0.001472 -0.010056 0.014058 0.304798 10.121485\n14621 59.241674 -0.003706 -0.001827 -0.009806 0.010302 0.288911 10.112221\n14622 59.247818 -0.003922 -0.002651 -0.009400 0.015925 0.315787 10.102332\n14623 59.253904 -0.003765 -0.003050 -0.009668 0.016053 0.329030 10.106761\n14624 59.259877 -0.003795 -0.003177 -0.009807 0.019512 0.319640 10.090529\n14625 59.266013 -0.004046 -0.003054 -0.009782 0.011218 0.317044 10.091498\n14626 59.271865 -0.004640 -0.002880 -0.010434 -0.000697 0.330929 10.096717\n14627 59.277846 -0.004489 -0.002586 -0.010899 0.004829 0.330793 10.099034\n14628 59.283958 -0.004273 -0.002621 -0.010785 0.011763 0.308657 10.106077\n14629 59.289983 -0.004243 -0.002993 -0.010418 0.010221 0.313041 10.094514\n14630 59.296043 -0.004052 -0.003486 -0.009971 0.016978 0.323075 10.103274\n14631 59.301975 -0.004034 -0.003593 -0.009737 0.017613 0.327997 10.117793\n14632 59.308213 -0.004337 -0.002838 -0.009610 0.022636 0.320915 10.114336\n14633 59.314125 -0.004368 -0.002173 -0.009868 0.014601 0.318000 10.120181\n14634 59.320152 -0.003780 -0.001646 -0.010506 0.014505 0.327524 10.121767\n14635 59.326147 -0.003438 -0.002078 -0.010596 0.018139 0.322780 10.122171\n14636 59.332532 -0.004414 -0.002365 -0.010413 0.026681 0.309312 10.113318\n14637 59.338388 -0.004512 -0.002465 -0.010007 0.024075 0.316053 10.094110\n14638 59.344251 -0.003859 -0.002635 -0.009522 0.010190 0.334265 10.085477\n14639 59.350262 -0.003852 -0.002518 -0.009470 -0.001153 0.330560 10.091651\n14640 59.356390 -0.004592 -0.001942 -0.009570 -0.006024 0.318794 10.108621\n14641 59.362386 -0.004790 -0.002029 -0.009587 0.001536 0.323050 10.116031\n14642 59.368517 -0.004769 -0.002637 -0.010064 0.019569 0.330911 10.117379\n14643 59.374513 -0.004517 -0.002593 -0.010085 0.022764 0.320365 10.103349\n14644 59.380517 -0.004634 -0.002795 -0.010415 0.012331 0.313011 10.060814\n14645 59.386707 -0.004576 -0.002767 -0.010496 0.005310 0.328036 10.063807\n14646 59.392528 -0.004468 -0.002082 -0.010250 0.000475 0.335780 10.103084\n14647 59.398869 -0.004346 -0.002084 -0.010073 -0.005261 0.329755 10.106202\n"
  },
  {
    "path": "matlab/range_measure_fit.m",
    "content": "function [range_trans, range_outlier_mask] = range_measure_fit(GT, TL, TD)\r\n%RANGE_MEASURE_FIT fit range measurment bias be least-square with ground\r\n%truth\r\n%   Detailed explanation goes here\r\n\r\n% Range fitting for the Plaza dataset using least square\r\nnr_pose = size(GT, 1);       % time step to investigate\r\nnr_range = size(TD, 1);       % time step to investigate\r\nT = GT(:,1);\r\n\r\n%% Construct data\r\n% Landmark locations ground truth\r\nlx = TL(:,2);    \r\nly = TL(:,3);\r\nl_true = [lx, ly];\r\n% forward / inverse map of landmark index\r\nLindx = TL(:,1);\r\nLindx_inv = zeros(max(Lindx)+1, 1);\r\nfor i=1:numel(Lindx)\r\n    Lindx_inv(Lindx(i)+1) = i;\r\nend\r\n\r\n% Landmark range measurements\r\nRange = zeros(nr_range, 3);    % [time index, landmark index, range; ... ]\r\nv = 1;      % the current range measurement index\r\nt = TD(v, 1);           % when the current range measurement took place\r\ni = 1;      % pose indx\r\nwhile i <= nr_pose && v <= nr_range\r\n    % Already passed the range measurement?\r\n    t = TD(v, 1);\r\n    if (T(i) >= t)\r\n        % See the range measure is close to which time index\r\n        % If close to i-1\r\n        if abs(T(i-1) - t) <= abs(T(i)-t)\r\n            Range(v,1) = i-1;\r\n        else\r\n            Range(v,1) = i;\r\n        end\r\n        Range(v,2) = Lindx_inv(TD(v,3)+1);\r\n        Range(v,3) = TD(v,4);\r\n        v = v+1;\r\n    else\r\n        i = i+1;\r\n    end\r\nend\r\n\r\n\r\ntrue_range = zeros(nr_range, 1);\r\nmeasured_range = zeros(nr_range, 1);\r\nfor i = 1:nr_range\r\n    x = GT(Range(i, 1), 2:3)';\r\n    l = l_true(Range(i, 2), :)';\r\n    true_range(i) = sqrt(sum((x-l).^2) );\r\n    measured_range(i) = Range(i, 3);\r\nend\r\n\r\n%% Least square\r\nb = true_range;\r\nA = [measured_range ones(nr_range, 1)];\r\nx = A \\ b;\r\nrange_trans = x;\r\n\r\n%% outlier mask\r\nrange_outlier_mask = zeros(nr_range, 1);\r\noutlier_limit = 2.0;\r\nfor i=1:nr_range\r\n    fit_range = range_trans(1) * measured_range(i) + range_trans(2);\r\n    if abs(fit_range - true_range(i)) > outlier_limit\r\n        range_outlier_mask(i) = 1;\r\n    else\r\n        range_outlier_mask(i) = 0;\r\n    end\r\nend\r\n\r\nmeas_range_inlier = [];\r\ntrue_range_inlier = [];\r\nmeas_range_outlier = [];\r\ntrue_range_outlier = [];\r\nfor i=1:nr_range\r\n    if range_outlier_mask(i)\r\n        meas_range_outlier = [meas_range_outlier; measured_range(i)];\r\n        true_range_outlier = [true_range_outlier; true_range(i)];\r\n    else\r\n        meas_range_inlier = [meas_range_inlier; measured_range(i)];\r\n        true_range_inlier = [true_range_inlier; true_range(i)];\r\n    end\r\nend\r\n\r\n%% update estimate by inliers\r\nb = true_range_inlier;\r\nA = [meas_range_inlier ones(numel(meas_range_inlier), 1)];\r\nx = A \\ b;\r\nrange_trans = x;\r\n\r\n% %% plot\r\n% figure(100)\r\n% hold on\r\n% title('Measurements fitting')\r\n% \r\n% plot(true_range_inlier, meas_range_inlier, 'b+')\r\n% \r\n% meas_range_updated = range_trans(1) * meas_range_inlier + range_trans(2);\r\n% plot(true_range_inlier, meas_range_updated, 'g+')\r\n% \r\n% plot([0, max(true_range_inlier)], [0, max(true_range_inlier)], 'k-')\r\n% \r\n% plot(true_range_outlier, meas_range_outlier, 'r+')\r\n% \r\n% legend('Raw inlier', 'Fitted inlier', 'Y = X', 'Raw outlier')\r\n% xlabel('Ground Truth Range (m)')\r\n% ylabel('Measured/Fitted Range (m)')\r\n% hold off\r\n\r\n\r\n\r\n\r\n"
  }
]